From 40f709d49083b6645cbaa6bef581edebb3f4d2d8 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 15 Sep 2023 19:05:45 +0200 Subject: [PATCH 1/8] Merge RotationRaw in Rotation and deprecated RotationRaw --- src/core/CMakeLists.txt | 1 - src/core/include/iDynTree/ClassicalAcc.h | 4 +- src/core/include/iDynTree/Core/RotationRaw.h | 4 +- src/core/include/iDynTree/PositionRaw.h | 2 +- src/core/include/iDynTree/Rotation.h | 34 +-- src/core/include/iDynTree/RotationRaw.h | 137 +---------- src/core/src/Rotation.cpp | 229 +++++++++++++------ src/core/src/RotationRaw.cpp | 218 ------------------ 8 files changed, 186 insertions(+), 443 deletions(-) delete mode 100644 src/core/src/RotationRaw.cpp diff --git a/src/core/CMakeLists.txt b/src/core/CMakeLists.txt index b25c333bbd..c7b8b5e9f0 100644 --- a/src/core/CMakeLists.txt +++ b/src/core/CMakeLists.txt @@ -52,7 +52,6 @@ set(IDYNTREE_CORE_EXP_SOURCES src/Axis.cpp src/Position.cpp src/PositionRaw.cpp src/Rotation.cpp - src/RotationRaw.cpp src/RotationalInertiaRaw.cpp src/SpatialAcc.cpp src/SpatialForceVector.cpp diff --git a/src/core/include/iDynTree/ClassicalAcc.h b/src/core/include/iDynTree/ClassicalAcc.h index 63a2025172..ae6cd75c74 100644 --- a/src/core/include/iDynTree/ClassicalAcc.h +++ b/src/core/include/iDynTree/ClassicalAcc.h @@ -8,7 +8,7 @@ namespace iDynTree { - class RotationRaw; + class Rotation; class SpatialAcc; class Twist; @@ -44,7 +44,7 @@ namespace iDynTree ClassicalAcc(const ClassicalAcc& other); /* Geometric operations */ - const ClassicalAcc & changeCoordFrame(const RotationRaw & newCoordFrame); + const ClassicalAcc & changeCoordFrame(const Rotation & newCoordFrame); /** constructor helpers */ static ClassicalAcc Zero(); diff --git a/src/core/include/iDynTree/Core/RotationRaw.h b/src/core/include/iDynTree/Core/RotationRaw.h index 1394e898f5..c78242e46f 100644 --- a/src/core/include/iDynTree/Core/RotationRaw.h +++ b/src/core/include/iDynTree/Core/RotationRaw.h @@ -5,9 +5,9 @@ #define IDYNTREE_CORE_ROTATION_RAW_H #ifdef __DEPRECATED - #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. #endif -#include +#include #endif diff --git a/src/core/include/iDynTree/PositionRaw.h b/src/core/include/iDynTree/PositionRaw.h index 4190e53a53..8e32e3c1f4 100644 --- a/src/core/include/iDynTree/PositionRaw.h +++ b/src/core/include/iDynTree/PositionRaw.h @@ -10,7 +10,7 @@ namespace iDynTree { - class RotationRaw; + class Rotation; class SpatialMotionVector; class SpatialForceVector; diff --git a/src/core/include/iDynTree/Rotation.h b/src/core/include/iDynTree/Rotation.h index 0ac0fef1df..fca7b3b957 100644 --- a/src/core/include/iDynTree/Rotation.h +++ b/src/core/include/iDynTree/Rotation.h @@ -6,8 +6,9 @@ #include #include -#include +#include #include +#include namespace iDynTree { @@ -38,14 +39,16 @@ namespace iDynTree * IEEE Robotics & Automation Magazine, Vol. 20, No. 1, pp. 84-93. * URL : http://people.mech.kuleuven.be/~tdelaet/geometric_relations_semantics/geometric_relations_semantics_theory.pdf * - * Given that this class uses the rotation matrix to represent orientation, some operation - * are disable because there is a semantic constraint induced by choice of representation, i.e. - * that the coordinate frame is always the reference orientation frame. Thus, some semantic operation - * are not enabled, namely: - * * the generic inverse, that does not change the coordinate frame. - * * changeCoordFrame, because CoordFrame is always the same of RefOrientFrame. + * Storage for the Orientation: + * + * The rotation matrix representation of the orientation, stored in row major order, + * inside a Matrix3x3 parent object. + * + * \warning This class uses for convenience the Matrix3x3 as a public parent. + * Notice that using this methods you can damage the underlyng rotation matrix. + * In doubt, don't use them and rely on more high level functions. */ - class Rotation: public RotationRaw + class Rotation : public Matrix3x3 { public: /** @@ -62,11 +65,6 @@ namespace iDynTree double yx, double yy, double yz, double zx, double zy, double zz); - /** - * Copy constructor: create a Rotation from another RotationRaw. - */ - Rotation(const RotationRaw & other); - /** * Copy constructor: create a Rotation from another Rotation. */ @@ -77,6 +75,14 @@ namespace iDynTree */ Rotation(iDynTree::MatrixView other); + /** + * Constructor from a buffer of 9 doubles, + * stored as a C-style array (i.e. row major). + * + */ + Rotation(const double* in_data, + const unsigned int in_rows, + const unsigned int in_cols); /** * Geometric operations. * For the inverse2() operation, both the forward and the inverse geometric relations have to @@ -468,6 +474,8 @@ namespace iDynTree std::string reservedToString() const; ///@} }; + + IDYNTREE_DEPRECATED_WITH_MSG("iDynTree::RotationRaw is deprecated, use iDynTree::Rotation") typedef Rotation RotationRaw; } #endif diff --git a/src/core/include/iDynTree/RotationRaw.h b/src/core/include/iDynTree/RotationRaw.h index e7fb9ae382..2eb3685bef 100644 --- a/src/core/include/iDynTree/RotationRaw.h +++ b/src/core/include/iDynTree/RotationRaw.h @@ -4,137 +4,10 @@ #ifndef IDYNTREE_ROTATION_RAW_H #define IDYNTREE_ROTATION_RAW_H -#include -#include - -namespace iDynTree -{ - class PositionRaw; - class SpatialMotionVector; - class SpatialForceVector; - class ClassicalAcc; - class RotationalInertiaRaw; - template - class MatrixView; - - /** - * Class providing the raw coordinates for iDynTree::Rotation class. - * - * Storage for the Orientation: - * The rotation matrix representation of the orientation, stored in row major order, - * inside a Matrix3x3 parent object. - * - * \note This implementation is compatible with KDL::Rotation data. - * - * \warning This class uses for convenience the Matrix3x3 as a public parent. - * Notice that using this methods you can damage the underlyng rotation matrix. - * In doubt, don't use them and rely on more high level functions. - * - * \ingroup iDynTreeCore - */ - class RotationRaw: public Matrix3x3 - { - public: - /** - * Default constructor. - * The data is not reset to identity for perfomance reason. - * Please initialize the data in the vector before any use. - */ - RotationRaw(); - - /** - * Constructor from 9 doubles: initialize elements of the rotation matrix. - */ - RotationRaw(double xx, double xy, double xz, - double yx, double yy, double yz, - double zx, double zy, double zz); - - /** - * Constructor from a buffer of 9 doubles, - * stored as a C-style array (i.e. row major). - * - */ - RotationRaw(const double* in_data, - const unsigned int in_rows, - const unsigned int in_cols); - - RotationRaw(iDynTree::MatrixView other); - - /** - * Copy constructor: create a RotationRaw from another RotationRaw. - */ - RotationRaw(const RotationRaw & other); - - /** - * Geometric operations. - */ - const RotationRaw & changeOrientFrame(const RotationRaw & newOrientFrame); - const RotationRaw & changeRefOrientFrame(const RotationRaw & newRefOrientFrame); - static RotationRaw compose(const RotationRaw & op1, const RotationRaw & op2); - static RotationRaw inverse2(const RotationRaw & orient); - PositionRaw changeCoordFrameOf(const PositionRaw & other) const; - ClassicalAcc changeCoordFrameOf(const ClassicalAcc & other) const; - RotationalInertiaRaw changeCoordFrameOf(const RotationalInertiaRaw & other) const; - - - - /** - * overloaded operators - */ - - /** - * @name Initialization helpers. - * - */ - ///@{ - - /** - * Return a Rotation around axis X of given angle - * - * @param angle the angle (in Radians) of the rotation arount the X axis - */ - static RotationRaw RotX(const double angle); - - /** - * Return a Rotation around axis Y of given angle - * - * @param angle the angle (in Radians) of the rotation arount the Y axis - */ - static RotationRaw RotY(const double angle); - - /** - * Return a Rotation around axis Z of given angle - * - * @param angle the angle (in Radians) of the rotation arount the Z axis - */ - static RotationRaw RotZ(const double angle); - - /** - * Return a rotation object given Roll, Pitch and Yaw values. - * - * @note This method is compatible with the KDL::Rotation::RPY method. - */ - static RotationRaw RPY(const double roll, const double pitch, const double yaw); - - /** - * Return an identity rotation. - * - * - */ - static RotationRaw Identity(); - - ///@} - - - /** @name Output helpers. - * Output helpers. - */ - ///@{ - std::string toString() const; +#ifdef __DEPRECATED + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. +#endif - std::string reservedToString() const; - ///@} - }; -} +#include -#endif +#endif \ No newline at end of file diff --git a/src/core/src/Rotation.cpp b/src/core/src/Rotation.cpp index c030961bb8..4cb52d9824 100644 --- a/src/core/src/Rotation.cpp +++ b/src/core/src/Rotation.cpp @@ -12,6 +12,7 @@ #include #include #include +#include #include #include @@ -22,6 +23,9 @@ #include #include +typedef Eigen::Matrix Matrix3dRowMajor; +typedef Eigen::Matrix Vector6d; + namespace iDynTree { /** @@ -44,41 +48,57 @@ namespace iDynTree typedef Eigen::Matrix Matrix3dRowMajor; - Rotation::Rotation(): RotationRaw() + Rotation::Rotation() { } Rotation::Rotation(double xx, double xy, double xz, double yx, double yy, double yz, - double zx, double zy, double zz): RotationRaw(xx,xy,xz, - yx,yy,yz, - zx,zy,zz) + double zx, double zy, double zz) { + this->m_data[0] = xx; + this->m_data[1] = xy; + this->m_data[2] = xz; + this->m_data[3] = yx; + this->m_data[4] = yy; + this->m_data[5] = yz; + this->m_data[6] = zx; + this->m_data[7] = zy; + this->m_data[8] = zz; } - Rotation::Rotation(const Rotation & other): RotationRaw(other) - { - } + Rotation::Rotation(const Rotation& other): + MatrixFixSize<3, 3>(other) + {} - Rotation::Rotation(const RotationRaw& other): RotationRaw(other) - { - } + Rotation::Rotation(MatrixView other): + MatrixFixSize<3, 3>(other) + {} - Rotation::Rotation(MatrixView other): RotationRaw(other) + Rotation::Rotation(const double* in_data, const unsigned int in_rows, const unsigned int in_cols): + MatrixFixSize<3, 3>(in_data,in_rows,in_cols) { } const Rotation& Rotation::changeOrientFrame(const Rotation& newOrientFrame) { - this->RotationRaw::changeOrientFrame(newOrientFrame); + Eigen::Map thisData(this->m_data); + Eigen::Map newOrientFrameData(newOrientFrame.data()); + + thisData = thisData*newOrientFrameData; + return *this; } const Rotation& Rotation::changeRefOrientFrame(const Rotation& newRefOrientFrame) { - this->RotationRaw::changeRefOrientFrame(newRefOrientFrame); + Eigen::Map thisData(this->m_data); + Eigen::Map newRefOrientFrameData(newRefOrientFrame.data()); + + thisData = newRefOrientFrameData*thisData; + return *this; } @@ -89,17 +109,136 @@ namespace iDynTree Rotation Rotation::compose(const Rotation& op1, const Rotation& op2) { - return Rotation(RotationRaw::compose(op1,op2)); + Rotation result; + + Eigen::Map op1Data(op1.m_data); + Eigen::Map op2Data(op2.m_data); + Eigen::Map resultData(result.m_data); + + resultData = op1Data*op2Data; + + return result; } Rotation Rotation::inverse2(const Rotation& orient) { - return Rotation(RotationRaw::inverse2(orient)); + Rotation result; + + Eigen::Map orientData(orient.m_data); + Eigen::Map resultData(result.m_data); + + resultData = orientData.transpose(); + + return result; } Position Rotation::changeCoordFrameOf(const Position & other) const { - return Position(this->RotationRaw::changeCoordFrameOf(other)); + Position result; + + Eigen::Map newCoordFrame(m_data); + Eigen::Map positionCoord(other.data()); + Eigen::Map resultData(result.data()); + + resultData = newCoordFrame*positionCoord; + + return result; + } + + ClassicalAcc Rotation::changeCoordFrameOf(const ClassicalAcc& other) const + { + ClassicalAcc result; + + Eigen::Map op1Rot(this->data()); + Eigen::Map op2Wrench(other.data()); + + Eigen::Map res(result.data()); + + res.segment<3>(3) = op1Rot*(op2Wrench.segment<3>(3)); + res.segment<3>(0) = op1Rot*(op2Wrench.segment<3>(0)); + + return result; + } + + RotationalInertiaRaw Rotation::changeCoordFrameOf(const RotationalInertiaRaw& other) const + { + RotationalInertiaRaw result; + + Eigen::Map op1Rot(this->data()); + Eigen::Map op2Inertia3d(other.data()); + + + Eigen::Map resInertia3d(result.data()); + + resInertia3d = op1Rot*op2Inertia3d*op1Rot.transpose(); + + return result; + } + + + Rotation Rotation::RotX(const double angle) + { + Rotation result; + Eigen::Map thisData(result.data()); + thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitX()).matrix(); + + return result; + } + + Rotation Rotation::RotY(const double angle) + { + Rotation result; + Eigen::Map thisData(result.data()); + thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitY()).matrix(); + + return result; + } + + Rotation Rotation::RotZ(const double angle) + { + Rotation result; + Eigen::Map thisData(result.data()); + thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitZ()).matrix(); + + return result; + } + + Rotation Rotation::RPY(const double roll, const double pitch, const double yaw) + { + return compose(RotZ(yaw), compose(RotY(pitch), RotX(roll))); + } + + Rotation Rotation::Identity() + { + Rotation result; + Eigen::Map thisData(result.data()); + + thisData.setIdentity(); + + return result; + } + + + std::string Rotation::toString() const + { + std::stringstream ss; + + ss << this->m_data[0] + << " " << this->m_data[1] + << " " << this->m_data[2] << std::endl; + ss << this->m_data[3] + << " " << this->m_data[4] + << " " << this->m_data[5] << std::endl; + ss << this->m_data[6] + << " " << this->m_data[7] + << " " << this->m_data[8] << std::endl; + + return ss.str(); + } + + std::string Rotation::reservedToString() const + { + return this->toString(); } SpatialMotionVector Rotation::changeCoordFrameOf(const SpatialMotionVector& other) const @@ -145,23 +284,6 @@ namespace iDynTree return result; } - ClassicalAcc Rotation::changeCoordFrameOf(const ClassicalAcc &other) const - { - ClassicalAcc result; - result = RotationRaw::changeCoordFrameOf(other); - - return result; - } - - RotationalInertiaRaw Rotation::changeCoordFrameOf(const RotationalInertiaRaw &other) const - { - RotationalInertiaRaw result; - - result = RotationRaw::changeCoordFrameOf(other); - - return result; - } - Axis Rotation::changeCoordFrameOf(const Axis& other) const { return Axis(this->changeCoordFrameOf(other.getDirection()),this->changeCoordFrameOf(other.getOrigin())); @@ -418,21 +540,6 @@ namespace iDynTree return ret; } - Rotation Rotation::RotX(const double angle) - { - return Rotation(RotationRaw::RotX(angle)); - } - - Rotation Rotation::RotY(const double angle) - { - return Rotation(RotationRaw::RotY(angle)); - } - - Rotation Rotation::RotZ(const double angle) - { - return Rotation(RotationRaw::RotZ(angle)); - } - Rotation Rotation::RotAxis(const Direction & direction, const double angle) { Rotation result; @@ -456,11 +563,6 @@ namespace iDynTree return result; } - Rotation Rotation::RPY(const double roll, const double pitch, const double yaw) - { - return Rotation(RotationRaw::RPY(roll, pitch, yaw)); - } - Matrix3x3 Rotation::RPYRightTrivializedDerivative(const double /*roll*/, const double pitch, const double yaw) { // See doc/symbolic/RPYExpressionReference.py @@ -581,11 +683,6 @@ namespace iDynTree return outputMatrix; } - Rotation Rotation::Identity() - { - return RotationRaw::Identity(); - } - Rotation Rotation::RotationFromQuaternion(const iDynTree::Vector4& _quaternion) { //Taken from "Contributions au contrôle automatique de véhicules aériens" @@ -663,20 +760,4 @@ namespace iDynTree toEigen(Jinv) = alpha1*I3 + alpha2*toEigen(phi_cross) + alpha3*toEigen(phi)*toEigen(phi).transpose(); return Jinv; } - - std::string Rotation::toString() const - { - std::stringstream ss; - - ss << RotationRaw::toString(); - - return ss.str(); - } - - std::string Rotation::reservedToString() const - { - return this->toString(); - } - - } diff --git a/src/core/src/RotationRaw.cpp b/src/core/src/RotationRaw.cpp deleted file mode 100644 index 74905b63cf..0000000000 --- a/src/core/src/RotationRaw.cpp +++ /dev/null @@ -1,218 +0,0 @@ -// SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) -// SPDX-License-Identifier: BSD-3-Clause - - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include - - -typedef Eigen::Matrix Matrix3dRowMajor; -typedef Eigen::Matrix Vector6d; - - -namespace iDynTree -{ - RotationRaw::RotationRaw() - { - } - - RotationRaw::RotationRaw(double xx, double xy, double xz, - double yx, double yy, double yz, - double zx, double zy, double zz) - { - this->m_data[0] = xx; - this->m_data[1] = xy; - this->m_data[2] = xz; - this->m_data[3] = yx; - this->m_data[4] = yy; - this->m_data[5] = yz; - this->m_data[6] = zx; - this->m_data[7] = zy; - this->m_data[8] = zz; - } - - RotationRaw::RotationRaw(MatrixView other): - MatrixFixSize<3, 3>(other) - {} - - RotationRaw::RotationRaw(const double* in_data, const unsigned int in_rows, const unsigned int in_cols): - MatrixFixSize<3, 3>(in_data,in_rows,in_cols) - { - - } - - - RotationRaw::RotationRaw(const RotationRaw& other):MatrixFixSize< int(3), int(3) >(other) - { - Eigen::Map thisData(this->m_data); - Eigen::Map otherData(other.m_data); - - thisData = otherData; - } - - const RotationRaw& RotationRaw::changeOrientFrame(const RotationRaw& /*newOrientFrame*/) - { - Eigen::Map thisData(this->m_data); - Eigen::Map newOrientFrameData(this->m_data); - - thisData = thisData*newOrientFrameData; - - return *this; - } - - const RotationRaw& RotationRaw::changeRefOrientFrame(const RotationRaw& /*newRefOrientFrame*/) - { - Eigen::Map thisData(this->m_data); - Eigen::Map newRefOrientFrameData(this->m_data); - - thisData = newRefOrientFrameData*thisData; - - return *this; - } - - RotationRaw RotationRaw::compose(const RotationRaw& op1, const RotationRaw& op2) - { - RotationRaw result; - - Eigen::Map op1Data(op1.m_data); - Eigen::Map op2Data(op2.m_data); - Eigen::Map resultData(result.m_data); - - resultData = op1Data*op2Data; - - return result; - } - - RotationRaw RotationRaw::inverse2(const RotationRaw& orient) - { - RotationRaw result; - - Eigen::Map orientData(orient.m_data); - Eigen::Map resultData(result.m_data); - - resultData = orientData.transpose(); - - return result; - } - - PositionRaw RotationRaw::changeCoordFrameOf(const PositionRaw & other) const - { - PositionRaw result; - - Eigen::Map newCoordFrame(m_data); - Eigen::Map positionCoord(other.data()); - Eigen::Map resultData(result.data()); - - resultData = newCoordFrame*positionCoord; - - return result; - } - - ClassicalAcc RotationRaw::changeCoordFrameOf(const ClassicalAcc& other) const - { - ClassicalAcc result; - - Eigen::Map op1Rot(this->data()); - Eigen::Map op2Wrench(other.data()); - - Eigen::Map res(result.data()); - - res.segment<3>(3) = op1Rot*(op2Wrench.segment<3>(3)); - res.segment<3>(0) = op1Rot*(op2Wrench.segment<3>(0)); - - return result; - } - - RotationalInertiaRaw RotationRaw::changeCoordFrameOf(const RotationalInertiaRaw& other) const - { - RotationalInertiaRaw result; - - Eigen::Map op1Rot(this->data()); - Eigen::Map op2Inertia3d(other.data()); - - - Eigen::Map resInertia3d(result.data()); - - resInertia3d = op1Rot*op2Inertia3d*op1Rot.transpose(); - - return result; - } - - - RotationRaw RotationRaw::RotX(const double angle) - { - RotationRaw result; - Eigen::Map thisData(result.data()); - thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitX()).matrix(); - - return result; - } - - RotationRaw RotationRaw::RotY(const double angle) - { - RotationRaw result; - Eigen::Map thisData(result.data()); - thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitY()).matrix(); - - return result; - } - - RotationRaw RotationRaw::RotZ(const double angle) - { - RotationRaw result; - Eigen::Map thisData(result.data()); - thisData = Eigen::AngleAxisd(angle, Eigen::Vector3d::UnitZ()).matrix(); - - return result; - } - - RotationRaw RotationRaw::RPY(const double roll, const double pitch, const double yaw) - { - return compose(RotZ(yaw), compose(RotY(pitch), RotX(roll))); - } - - RotationRaw RotationRaw::Identity() - { - RotationRaw result; - Eigen::Map thisData(result.data()); - - thisData.setIdentity(); - - return result; - } - - - std::string RotationRaw::toString() const - { - std::stringstream ss; - - ss << this->m_data[0] - << " " << this->m_data[1] - << " " << this->m_data[2] << std::endl; - ss << this->m_data[3] - << " " << this->m_data[4] - << " " << this->m_data[5] << std::endl; - ss << this->m_data[6] - << " " << this->m_data[7] - << " " << this->m_data[8] << std::endl; - - return ss.str(); - } - - std::string RotationRaw::reservedToString() const - { - return this->toString(); - } - - -} From deea1a161e18f24f2ce94175bd3836015411a6cd Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Fri, 15 Sep 2023 19:19:59 +0200 Subject: [PATCH 2/8] Merge PositionRaw in Position and deprecated PositionRaw --- src/core/CMakeLists.txt | 1 - src/core/include/iDynTree/Core/PositionRaw.h | 4 +- src/core/include/iDynTree/Position.h | 10 +- src/core/include/iDynTree/PositionRaw.h | 74 +--------- .../include/iDynTree/RotationalInertiaRaw.h | 2 +- src/core/include/iDynTree/SpatialInertiaRaw.h | 8 +- src/core/src/Position.cpp | 111 +++++++++----- src/core/src/PositionRaw.cpp | 137 ------------------ 8 files changed, 95 insertions(+), 252 deletions(-) delete mode 100644 src/core/src/PositionRaw.cpp diff --git a/src/core/CMakeLists.txt b/src/core/CMakeLists.txt index c7b8b5e9f0..5c51da66a7 100644 --- a/src/core/CMakeLists.txt +++ b/src/core/CMakeLists.txt @@ -50,7 +50,6 @@ set(IDYNTREE_CORE_EXP_SOURCES src/Axis.cpp src/MatrixDynSize.cpp src/GeomVector3.cpp src/Position.cpp - src/PositionRaw.cpp src/Rotation.cpp src/RotationalInertiaRaw.cpp src/SpatialAcc.cpp diff --git a/src/core/include/iDynTree/Core/PositionRaw.h b/src/core/include/iDynTree/Core/PositionRaw.h index b7e60bf1b6..3f3b9b086e 100644 --- a/src/core/include/iDynTree/Core/PositionRaw.h +++ b/src/core/include/iDynTree/Core/PositionRaw.h @@ -5,9 +5,9 @@ #define IDYNTREE_CORE_POSITION_RAW_H #ifdef __DEPRECATED - #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. #endif -#include +#include #endif diff --git a/src/core/include/iDynTree/Position.h b/src/core/include/iDynTree/Position.h index 0aa78c02de..df9a36f7b5 100644 --- a/src/core/include/iDynTree/Position.h +++ b/src/core/include/iDynTree/Position.h @@ -4,7 +4,6 @@ #ifndef IDYNTREE_POSITION_H #define IDYNTREE_POSITION_H -#include #include #include @@ -32,7 +31,7 @@ namespace iDynTree * respect to an orientation given by *orientFrame* . * */ - class Position: public PositionRaw + class Position: public Vector3 { public: /** @@ -52,9 +51,9 @@ namespace iDynTree Position(const Position & other); /** - * Copy constructor: create a Position from a PositionRaw + * Constructor from a raw buffer of 3 doubles. */ - Position(const PositionRaw & other); + Position(const double* in_data, const unsigned int in_size); /** * Create a Position from a span @@ -101,6 +100,9 @@ namespace iDynTree static Position Zero(); }; + + IDYNTREE_DEPRECATED_WITH_MSG("iDynTree::PositionRaw is deprecated, use iDynTree::Position") typedef Position PositionRaw; + } #endif diff --git a/src/core/include/iDynTree/PositionRaw.h b/src/core/include/iDynTree/PositionRaw.h index 8e32e3c1f4..d2d6cdac87 100644 --- a/src/core/include/iDynTree/PositionRaw.h +++ b/src/core/include/iDynTree/PositionRaw.h @@ -4,74 +4,10 @@ #ifndef IDYNTREE_POSITION_RAW_H #define IDYNTREE_POSITION_RAW_H +#ifdef __DEPRECATED + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. +#endif -#include -#include +#include -namespace iDynTree -{ - class Rotation; - class SpatialMotionVector; - class SpatialForceVector; - - /** - * Class providing the raw coordinates for iDynTree::Position class. - * - * \ingroup iDynTreeCore - */ - class PositionRaw: public Vector3 - { - public: - /** - * Default constructor. - * The data is not reset to 0 for perfomance reason. - * Please initialize the data in the vector before any use. - */ - PositionRaw(); - - /** - * Constructor from 3 doubles: initialize the coordinates with the passed values. - */ - PositionRaw(double x, double y, double z); - - /** - * Constructor from a raw buffer of 3 doubles. - */ - PositionRaw(const double* in_data, const unsigned int in_size); - - /** - * Copy constructor: create a PositionRaw from another PositionRaw - */ - PositionRaw(const PositionRaw & other); - - /** - * Construct from a span - * @warning if the Span size is different from 3 an assert is thrown at run-time. - */ - PositionRaw(iDynTree::Span other); - - /** - * Geometric operations - */ - const PositionRaw & changePoint(const PositionRaw & newPoint); - const PositionRaw & changeRefPoint(const PositionRaw & newRefPoint); - static PositionRaw compose(const PositionRaw & op1, const PositionRaw & op2); - static PositionRaw inverse(const PositionRaw & op); - SpatialMotionVector changePointOf(const SpatialMotionVector & other) const; - SpatialForceVector changePointOf(const SpatialForceVector & other) const; - - - /** @name Output helpers. - * Output helpers. - */ - ///@{ - std::string toString() const; - - std::string reservedToString() const; - ///@} - - }; - -} - -#endif /* IDYNTREE_POSITION_RAW_H */ +#endif \ No newline at end of file diff --git a/src/core/include/iDynTree/RotationalInertiaRaw.h b/src/core/include/iDynTree/RotationalInertiaRaw.h index 7f96b28f1a..b1c50215dd 100644 --- a/src/core/include/iDynTree/RotationalInertiaRaw.h +++ b/src/core/include/iDynTree/RotationalInertiaRaw.h @@ -8,7 +8,7 @@ namespace iDynTree { - class PositionRaw; + class Position; /** * Class providing the raw coordinates for a 3d inertia matrix. diff --git a/src/core/include/iDynTree/SpatialInertiaRaw.h b/src/core/include/iDynTree/SpatialInertiaRaw.h index cc21947dc5..a2678d7f49 100644 --- a/src/core/include/iDynTree/SpatialInertiaRaw.h +++ b/src/core/include/iDynTree/SpatialInertiaRaw.h @@ -8,7 +8,7 @@ namespace iDynTree { - class PositionRaw; + class Position; class SpatialForceVector; class SpatialMotionVector; @@ -45,7 +45,7 @@ namespace iDynTree * \warning the KDL::RigidBodyInertia class has a similar constructor, but in that one * the rotational inerta in input is expressed in the center of mass of the body. */ - SpatialInertiaRaw(const double mass, const PositionRaw & com, const RotationalInertiaRaw & rotInertia); + SpatialInertiaRaw(const double mass, const Position & com, const RotationalInertiaRaw & rotInertia); SpatialInertiaRaw(const SpatialInertiaRaw & other); /** @@ -53,7 +53,7 @@ namespace iDynTree * and the rotational inertia expressed in the center of mass. * */ - void fromRotationalInertiaWrtCenterOfMass(const double mass, const PositionRaw & com, const RotationalInertiaRaw & rotInertia); + void fromRotationalInertiaWrtCenterOfMass(const double mass, const Position& com, const RotationalInertiaRaw & rotInertia); /** multiplication operator @@ -73,7 +73,7 @@ namespace iDynTree * efficient. */ double getMass() const; - PositionRaw getCenterOfMass() const; + Position getCenterOfMass() const; const RotationalInertiaRaw& getRotationalInertiaWrtFrameOrigin() const; RotationalInertiaRaw getRotationalInertiaWrtCenterOfMass() const; diff --git a/src/core/src/Position.cpp b/src/core/src/Position.cpp index b9db130703..f2f5429562 100644 --- a/src/core/src/Position.cpp +++ b/src/core/src/Position.cpp @@ -15,6 +15,7 @@ #include #include + namespace iDynTree { /** @@ -41,70 +42,125 @@ namespace iDynTree newAngularVec); } - /** - * class Method definitions - */ - - Position::Position(): PositionRaw() + Position::Position() { } - Position::Position(double x, double y, double z): PositionRaw(x,y,z) + + Position::Position(double x, double y, double z) { + this->m_data[0] = x; + this->m_data[1] = y; + this->m_data[2] = z; } - Position::Position(const Position & other): PositionRaw(other) + Position::Position(const double* in_data, const unsigned int in_size): + VectorFixSize< 3 >(in_data,in_size) { + } - Position::Position(const PositionRaw& other): PositionRaw(other) + Position::Position(const Position& other):VectorFixSize< int(3) >(other) { + this->m_data[0] = other.m_data[0]; + this->m_data[1] = other.m_data[1]; + this->m_data[2] = other.m_data[2]; } - Position::Position(Span other): PositionRaw(other) + Position::Position(Span other): + VectorFixSize< 3 >(other) { + } const Position& Position::changePoint(const Position& newPoint) { - this->PositionRaw::changePoint(newPoint); + this->m_data[0] += newPoint(0); + this->m_data[1] += newPoint(1); + this->m_data[2] += newPoint(2); + return *this; } const Position& Position::changeRefPoint(const Position& newRefPoint) { - this->PositionRaw::changeRefPoint(newRefPoint); - return *this; - } + this->m_data[0] += newRefPoint(0); + this->m_data[1] += newRefPoint(1); + this->m_data[2] += newRefPoint(2); - const Position& Position::changeCoordinateFrame(const Rotation & newCoordinateFrame) - { - *this = newCoordinateFrame.changeCoordFrameOf(*this); return *this; } Position Position::compose(const Position& op1, const Position& op2) { - return Position(PositionRaw::compose(op1,op2)); + Position result; + result(0) = op1(0) + op2(0); + result(1) = op1(1) + op2(1); + result(2) = op1(2) + op2(2); + return result; } - Position Position::inverse(const Position& op) { - return Position(PositionRaw::inverse(op)); + Position result; + result(0) = -op.m_data[0]; + result(1) = -op.m_data[1]; + result(2) = -op.m_data[2]; + return result; } SpatialMotionVector Position::changePointOf(const SpatialMotionVector & other) const { - return changePointOfMotionT(*this, other); + SpatialMotionVector result; + + Eigen::Map thisPos(this->data()); + Eigen::Map otherLinear(other.getLinearVec3().data()); + Eigen::Map otherAngular(other.getAngularVec3().data()); + Eigen::Map resLinear(result.getLinearVec3().data()); + Eigen::Map resAngular(result.getAngularVec3().data()); + + resLinear = otherLinear + thisPos.cross(otherAngular); + resAngular = otherAngular; + + return result; } SpatialForceVector Position::changePointOf(const SpatialForceVector & other) const { - return changePointOfForceT(*this, other); + SpatialForceVector result; + + Eigen::Map thisPos(this->data()); + Eigen::Map otherLinear(other.getLinearVec3().data()); + Eigen::Map otherAngular(other.getAngularVec3().data()); + Eigen::Map resLinear(result.getLinearVec3().data()); + Eigen::Map resAngular(result.getAngularVec3().data()); + + resLinear = otherLinear; + resAngular = thisPos.cross(otherLinear) + otherAngular; + + return result; } + std::string Position::toString() const + { + std::stringstream ss; + ss << this->m_data[0] << " " << this->m_data[1] << " " << this->m_data[2]; + return ss.str(); + } + + std::string Position::reservedToString() const + { + return this->toString(); + } + + const Position& Position::changeCoordinateFrame(const Rotation & newCoordinateFrame) + { + *this = newCoordinateFrame.changeCoordFrameOf(*this); + return *this; + } + + Twist Position::changePointOf(const Twist & other) const { return changePointOfMotionT(*this, other); @@ -166,19 +222,6 @@ namespace iDynTree return changePointOfForceT(*this, other); } - std::string Position::toString() const - { - std::stringstream ss; - - ss << PositionRaw::toString(); - return ss.str(); - } - - std::string Position::reservedToString() const - { - return this->toString(); - } - Position Position::Zero() { Position ret; diff --git a/src/core/src/PositionRaw.cpp b/src/core/src/PositionRaw.cpp deleted file mode 100644 index d13a6ff29c..0000000000 --- a/src/core/src/PositionRaw.cpp +++ /dev/null @@ -1,137 +0,0 @@ -// SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) -// SPDX-License-Identifier: BSD-3-Clause - - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -typedef Eigen::Matrix Matrix3dRowMajor; -typedef Eigen::Matrix Vector6d; - - -namespace iDynTree -{ - PositionRaw::PositionRaw() - { - } - - - PositionRaw::PositionRaw(double x, double y, double z) - { - this->m_data[0] = x; - this->m_data[1] = y; - this->m_data[2] = z; - } - - PositionRaw::PositionRaw(const double* in_data, const unsigned int in_size): - VectorFixSize< 3 >(in_data,in_size) - { - - } - - PositionRaw::PositionRaw(const PositionRaw& other):VectorFixSize< int(3) >(other) - { - this->m_data[0] = other.m_data[0]; - this->m_data[1] = other.m_data[1]; - this->m_data[2] = other.m_data[2]; - - } - - PositionRaw::PositionRaw(Span other): - VectorFixSize< 3 >(other) - { - - } - - const PositionRaw& PositionRaw::changePoint(const PositionRaw& newPoint) - { - this->m_data[0] += newPoint(0); - this->m_data[1] += newPoint(1); - this->m_data[2] += newPoint(2); - - return *this; - } - - const PositionRaw& PositionRaw::changeRefPoint(const PositionRaw& newRefPoint) - { - this->m_data[0] += newRefPoint(0); - this->m_data[1] += newRefPoint(1); - this->m_data[2] += newRefPoint(2); - - return *this; - } - - PositionRaw PositionRaw::compose(const PositionRaw& op1, const PositionRaw& op2) - { - PositionRaw result; - result(0) = op1(0) + op2(0); - result(1) = op1(1) + op2(1); - result(2) = op1(2) + op2(2); - return result; - } - - PositionRaw PositionRaw::inverse(const PositionRaw& op) - { - PositionRaw result; - result(0) = -op.m_data[0]; - result(1) = -op.m_data[1]; - result(2) = -op.m_data[2]; - return result; - } - - SpatialMotionVector PositionRaw::changePointOf(const SpatialMotionVector & other) const - { - SpatialMotionVector result; - - Eigen::Map thisPos(this->data()); - Eigen::Map otherLinear(other.getLinearVec3().data()); - Eigen::Map otherAngular(other.getAngularVec3().data()); - Eigen::Map resLinear(result.getLinearVec3().data()); - Eigen::Map resAngular(result.getAngularVec3().data()); - - resLinear = otherLinear + thisPos.cross(otherAngular); - resAngular = otherAngular; - - return result; - } - - SpatialForceVector PositionRaw::changePointOf(const SpatialForceVector & other) const - { - SpatialForceVector result; - - Eigen::Map thisPos(this->data()); - Eigen::Map otherLinear(other.getLinearVec3().data()); - Eigen::Map otherAngular(other.getAngularVec3().data()); - Eigen::Map resLinear(result.getLinearVec3().data()); - Eigen::Map resAngular(result.getAngularVec3().data()); - - resLinear = otherLinear; - resAngular = thisPos.cross(otherLinear) + otherAngular; - - return result; - } - - std::string PositionRaw::toString() const - { - std::stringstream ss; - ss << this->m_data[0] << " " << this->m_data[1] << " " << this->m_data[2]; - return ss.str(); - } - - std::string PositionRaw::reservedToString() const - { - return this->toString(); - } - - - - -} From 8b98e746881d0c13ac7076a562c1c83f615b24c6 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sat, 16 Sep 2023 19:22:40 +0200 Subject: [PATCH 3/8] Rename RotationalInertiaRaw in RotationalInertia and deprecate RotationalInertiaRaw --- src/core/CMakeLists.txt | 3 +- .../iDynTree/Core/RotationalInertiaRaw.h | 4 +- src/core/include/iDynTree/Rotation.h | 6 +-- src/core/include/iDynTree/RotationalInertia.h | 49 +++++++++++++++++++ .../include/iDynTree/RotationalInertiaRaw.h | 44 ++--------------- src/core/src/Rotation.cpp | 8 +-- ...alInertiaRaw.cpp => RotationalInertia.cpp} | 12 ++--- 7 files changed, 71 insertions(+), 55 deletions(-) create mode 100644 src/core/include/iDynTree/RotationalInertia.h rename src/core/src/{RotationalInertiaRaw.cpp => RotationalInertia.cpp} (61%) diff --git a/src/core/CMakeLists.txt b/src/core/CMakeLists.txt index 5c51da66a7..bbd27197ea 100644 --- a/src/core/CMakeLists.txt +++ b/src/core/CMakeLists.txt @@ -15,6 +15,7 @@ set(IDYNTREE_CORE_EXP_HEADERS include/iDynTree/Axis.h include/iDynTree/PositionRaw.h include/iDynTree/Rotation.h include/iDynTree/RotationRaw.h + include/iDynTree/RotationalInertia.h include/iDynTree/RotationalInertiaRaw.h include/iDynTree/SpatialAcc.h include/iDynTree/SpatialForceVector.h @@ -51,7 +52,7 @@ set(IDYNTREE_CORE_EXP_SOURCES src/Axis.cpp src/GeomVector3.cpp src/Position.cpp src/Rotation.cpp - src/RotationalInertiaRaw.cpp + src/RotationalInertia.cpp src/SpatialAcc.cpp src/SpatialForceVector.cpp src/SpatialMomentum.cpp diff --git a/src/core/include/iDynTree/Core/RotationalInertiaRaw.h b/src/core/include/iDynTree/Core/RotationalInertiaRaw.h index 78a5c0b517..5c5c154110 100644 --- a/src/core/include/iDynTree/Core/RotationalInertiaRaw.h +++ b/src/core/include/iDynTree/Core/RotationalInertiaRaw.h @@ -5,9 +5,9 @@ #define IDYNTREE_CORE_ROTATIONAL_INERTIA_RAW_H #ifdef __DEPRECATED - #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. #endif -#include +#include #endif \ No newline at end of file diff --git a/src/core/include/iDynTree/Rotation.h b/src/core/include/iDynTree/Rotation.h index fca7b3b957..93d456586a 100644 --- a/src/core/include/iDynTree/Rotation.h +++ b/src/core/include/iDynTree/Rotation.h @@ -21,7 +21,7 @@ namespace iDynTree class SpatialAcc; class SpatialMomentum; class ClassicalAcc; - class RotationalInertiaRaw; + class RotationalInertia; class SpatialMotionVector; class SpatialForceVector; class ArticulatedBodyInertia; @@ -104,7 +104,7 @@ namespace iDynTree Direction changeCoordFrameOf(const Direction & other) const; Axis changeCoordFrameOf(const Axis & other) const; ClassicalAcc changeCoordFrameOf(const ClassicalAcc & other) const; - RotationalInertiaRaw changeCoordFrameOf(const RotationalInertiaRaw & other) const; + RotationalInertia changeCoordFrameOf(const RotationalInertia & other) const; /** @@ -121,7 +121,7 @@ namespace iDynTree SpatialAcc operator*(const SpatialAcc & other) const; SpatialMomentum operator*(const SpatialMomentum & other) const; ClassicalAcc operator*(const ClassicalAcc & other) const; - RotationalInertiaRaw operator*(const RotationalInertiaRaw & other) const; + RotationalInertia operator*(const RotationalInertia & other) const; /** * Log mapping between a generic element of SO(3) (iDynTree::Rotation) diff --git a/src/core/include/iDynTree/RotationalInertia.h b/src/core/include/iDynTree/RotationalInertia.h new file mode 100644 index 0000000000..69f181ffbe --- /dev/null +++ b/src/core/include/iDynTree/RotationalInertia.h @@ -0,0 +1,49 @@ +// SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) +// SPDX-License-Identifier: BSD-3-Clause + +#ifndef IDYNTREE_ROTATIONAL_INERTIA_H +#define IDYNTREE_ROTATIONAL_INERTIA_H + +#include + +namespace iDynTree +{ + class Position; + + /** + * Class providing the raw coordinates for a 3d inertia matrix. + * + * \ingroup iDynTreeCore + * + * \note in iDynTree, the spatial vector follows this serialization: the first three elements are + * the linear part and the second three elements are the angular part. + * + * We use a parent Matrix3x3 for storage of the rotational inertia matrix: + * given that the inertia matrix is a 3x3 symmetric matrix, + * the ordering (row order or column order) is not influencing + * the storage of the matrix. + */ + class RotationalInertia: public Matrix3x3 + { + + public: + /** + * Default constructor. + * The data is not reset to zero for perfomance reason. + * Please initialize the data in the vector before any use. + */ + RotationalInertia(); + RotationalInertia(const double * in_data, const unsigned int in_rows, const unsigned int in_cols); + RotationalInertia(const RotationalInertia & other); + + /** + * Initializer helper: return a zero matrix. + */ + static RotationalInertia Zero(); + + }; + + IDYNTREE_DEPRECATED_WITH_MSG("iDynTree::RotationalInertiaRaw is deprecated, use iDynTree::RotationalInertia") typedef RotationalInertia RotationalInertiaRaw; +} + +#endif /* IDYNTREE_ROTATIONAL_INERTIA_RAW_H */ diff --git a/src/core/include/iDynTree/RotationalInertiaRaw.h b/src/core/include/iDynTree/RotationalInertiaRaw.h index b1c50215dd..1397baf4fe 100644 --- a/src/core/include/iDynTree/RotationalInertiaRaw.h +++ b/src/core/include/iDynTree/RotationalInertiaRaw.h @@ -4,44 +4,10 @@ #ifndef IDYNTREE_ROTATIONAL_INERTIA_RAW_H #define IDYNTREE_ROTATIONAL_INERTIA_RAW_H -#include +#ifdef __DEPRECATED + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. +#endif -namespace iDynTree -{ - class Position; +#include - /** - * Class providing the raw coordinates for a 3d inertia matrix. - * - * \ingroup iDynTreeCore - * - * \note in iDynTree, the spatial vector follows this serialization: the first three elements are - * the linear part and the second three elements are the angular part. - * - * We use a parent Matrix3x3 for storage of the rotational inertia matrix: - * given that the inertia matrix is a 3x3 symmetric matrix, - * the ordering (row order or column order) is not influencing - * the storage of the matrix. - */ - class RotationalInertiaRaw: public Matrix3x3 - { - - public: - /** - * Default constructor. - * The data is not reset to zero for perfomance reason. - * Please initialize the data in the vector before any use. - */ - RotationalInertiaRaw(); - RotationalInertiaRaw(const double * in_data, const unsigned int in_rows, const unsigned int in_cols); - RotationalInertiaRaw(const RotationalInertiaRaw & other); - - /** - * Initializer helper: return a zero matrix. - */ - static RotationalInertiaRaw Zero(); - - }; -} - -#endif /* IDYNTREE_ROTATIONAL_INERTIA_RAW_H */ +#endif \ No newline at end of file diff --git a/src/core/src/Rotation.cpp b/src/core/src/Rotation.cpp index 4cb52d9824..87557c55de 100644 --- a/src/core/src/Rotation.cpp +++ b/src/core/src/Rotation.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include #include @@ -160,9 +160,9 @@ namespace iDynTree return result; } - RotationalInertiaRaw Rotation::changeCoordFrameOf(const RotationalInertiaRaw& other) const + RotationalInertia Rotation::changeCoordFrameOf(const RotationalInertia& other) const { - RotationalInertiaRaw result; + RotationalInertia result; Eigen::Map op1Rot(this->data()); Eigen::Map op2Inertia3d(other.data()); @@ -344,7 +344,7 @@ namespace iDynTree return changeCoordFrameOf(other); } - RotationalInertiaRaw Rotation::operator*(const RotationalInertiaRaw& other) const + RotationalInertia Rotation::operator*(const RotationalInertia& other) const { return changeCoordFrameOf(other); } diff --git a/src/core/src/RotationalInertiaRaw.cpp b/src/core/src/RotationalInertia.cpp similarity index 61% rename from src/core/src/RotationalInertiaRaw.cpp rename to src/core/src/RotationalInertia.cpp index fe2fcc4705..21bf51a32d 100644 --- a/src/core/src/RotationalInertiaRaw.cpp +++ b/src/core/src/RotationalInertia.cpp @@ -1,7 +1,7 @@ // SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) // SPDX-License-Identifier: BSD-3-Clause -#include +#include #include #include @@ -14,25 +14,25 @@ namespace iDynTree { -RotationalInertiaRaw::RotationalInertiaRaw() +RotationalInertia::RotationalInertia() { } -RotationalInertiaRaw::RotationalInertiaRaw(const double* in_data, +RotationalInertia::RotationalInertia(const double* in_data, const unsigned int in_rows, const unsigned int in_cols): Matrix3x3(in_data,in_rows,in_cols) { } -RotationalInertiaRaw::RotationalInertiaRaw(const RotationalInertiaRaw& other): Matrix3x3(other) +RotationalInertia::RotationalInertia(const RotationalInertia& other): Matrix3x3(other) { } -RotationalInertiaRaw RotationalInertiaRaw::Zero() +RotationalInertia RotationalInertia::Zero() { - RotationalInertiaRaw ret; + RotationalInertia ret; ret.zero(); return ret; } From fd954b9b73f66e898dbc7bdf5b36f8edd48bcb40 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sat, 16 Sep 2023 19:43:57 +0200 Subject: [PATCH 4/8] Merge SpatialInertiaRaw in SpatialInertia and deprecate SpatialInertiaRaw --- src/core/CMakeLists.txt | 1 - .../include/iDynTree/Core/SpatialInertiaRaw.h | 4 +- src/core/include/iDynTree/SpatialInertia.h | 51 ++++- src/core/include/iDynTree/SpatialInertiaRaw.h | 92 +-------- src/core/src/SpatialInertia.cpp | 157 +++++++++++++-- src/core/src/SpatialInertiaRaw.cpp | 181 ------------------ 6 files changed, 198 insertions(+), 288 deletions(-) delete mode 100644 src/core/src/SpatialInertiaRaw.cpp diff --git a/src/core/CMakeLists.txt b/src/core/CMakeLists.txt index bbd27197ea..00f94cd054 100644 --- a/src/core/CMakeLists.txt +++ b/src/core/CMakeLists.txt @@ -57,7 +57,6 @@ set(IDYNTREE_CORE_EXP_SOURCES src/Axis.cpp src/SpatialForceVector.cpp src/SpatialMomentum.cpp src/SpatialMotionVector.cpp - src/SpatialInertiaRaw.cpp src/SpatialInertia.cpp src/TestUtils.cpp src/Transform.cpp diff --git a/src/core/include/iDynTree/Core/SpatialInertiaRaw.h b/src/core/include/iDynTree/Core/SpatialInertiaRaw.h index a1a1643edc..c4b2640b5c 100644 --- a/src/core/include/iDynTree/Core/SpatialInertiaRaw.h +++ b/src/core/include/iDynTree/Core/SpatialInertiaRaw.h @@ -5,10 +5,10 @@ #define IDYNTREE_CORE_SPATIAL_INERTIA_RAW_H #ifdef __DEPRECATED - #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. #endif -#include +#include #endif diff --git a/src/core/include/iDynTree/SpatialInertia.h b/src/core/include/iDynTree/SpatialInertia.h index b1abdf606e..503715fc69 100644 --- a/src/core/include/iDynTree/SpatialInertia.h +++ b/src/core/include/iDynTree/SpatialInertia.h @@ -4,8 +4,8 @@ #ifndef IDYNTREE_SPATIAL_INERTIA_H #define IDYNTREE_SPATIAL_INERTIA_H -#include #include +#include #include #include #include @@ -19,8 +19,12 @@ namespace iDynTree * * \ingroup iDynTreeCore */ - class SpatialInertia: public SpatialInertiaRaw + class SpatialInertia { + protected: + double m_mass; ///< Mass. + double m_mcom[3]; ///< First moment of mass (i.e. mass * center of mass). + RotationalInertia m_rotInertia; ///< Three dimensional rotational inertia. public: /** * Default constructor. @@ -29,15 +33,52 @@ namespace iDynTree */ inline SpatialInertia() {} SpatialInertia(const double mass, - const PositionRaw & com, - const RotationalInertiaRaw & rotInertia); - SpatialInertia(const SpatialInertiaRaw& other); + const Position& com, + const RotationalInertia & rotInertia); SpatialInertia(const SpatialInertia& other); // Operations on SpatialInertia static SpatialInertia combine(const SpatialInertia & op1, const SpatialInertia & op2); + /** + * Helper constructor-like function that takes mass, center of mass + * and the rotational inertia expressed in the center of mass. + * + */ + void fromRotationalInertiaWrtCenterOfMass(const double mass, const Position& com, const RotationalInertia & rotInertia); + + + /** multiplication operator + * + * overloading happens on proper classes + * + */ + + + /** + * Getter functions + * + * \note for preserving consistency, no setters are implemented.. + * if you want to modify a spatial inertia create a new one, + * and assign it to the spatial inertia that you want modify. + * Given that no memory allocation happens it should be still + * efficient. + */ + double getMass() const; + Position getCenterOfMass() const; + const RotationalInertia& getRotationalInertiaWrtFrameOrigin() const; + RotationalInertia getRotationalInertiaWrtCenterOfMass() const; + + /** + * Multiplication function + * + */ + SpatialForceVector multiply(const SpatialMotionVector & op) const; + + /** reset to zero (i.e. the inertia of body with zero mass) the SpatialInertia */ + void zero(); + /** * @brief Get the SpatialInertia as a 6x6 matrix * diff --git a/src/core/include/iDynTree/SpatialInertiaRaw.h b/src/core/include/iDynTree/SpatialInertiaRaw.h index a2678d7f49..be568e2c1f 100644 --- a/src/core/include/iDynTree/SpatialInertiaRaw.h +++ b/src/core/include/iDynTree/SpatialInertiaRaw.h @@ -4,96 +4,12 @@ #ifndef IDYNTREE_SPATIAL_INERTIA_RAW_H #define IDYNTREE_SPATIAL_INERTIA_RAW_H -#include - -namespace iDynTree -{ - class Position; - class SpatialForceVector; - class SpatialMotionVector; - - /** - * Class providing the raw coordinates for a spatial inertia, i.e. - * a spatial dyadic mapping the motion space to the force space. - * - * \ingroup iDynTreeCore - * - * \note in iDynTree, the spatial vector follows this serialization: the first three elements are - * the linear part and the second three elements are the angular part. - */ - class SpatialInertiaRaw - { - protected: - double m_mass; ///< Mass. - double m_mcom[3]; ///< First moment of mass (i.e. mass * center of mass). - RotationalInertiaRaw m_rotInertia; ///< Three dimensional rotational inertia. - - public: - /** - * Default constructor. - * The data is not reset to zero for perfomance reason. - * Please initialize the data in the vector before any use. - */ - inline SpatialInertiaRaw() {} - - /** - * @param mass mass of the rigid body - * @param com center of mass of the rigid body, expressed in the frame - * in which the spatial inertia is expressed - * @param rotInertia rotational inertia expressed with respect to the origin of the frame. - * - * \warning the KDL::RigidBodyInertia class has a similar constructor, but in that one - * the rotational inerta in input is expressed in the center of mass of the body. - */ - SpatialInertiaRaw(const double mass, const Position & com, const RotationalInertiaRaw & rotInertia); - SpatialInertiaRaw(const SpatialInertiaRaw & other); - - /** - * Helper constructor-like function that takes mass, center of mass - * and the rotational inertia expressed in the center of mass. - * - */ - void fromRotationalInertiaWrtCenterOfMass(const double mass, const Position& com, const RotationalInertiaRaw & rotInertia); - - - /** multiplication operator - * - * overloading happens on proper classes - * - */ - - - /** - * Getter functions - * - * \note for preserving consistency, no setters are implemented.. - * if you want to modify a spatial inertia create a new one, - * and assign it to the spatial inertia that you want modify. - * Given that no memory allocation happens it should be still - * efficient. - */ - double getMass() const; - Position getCenterOfMass() const; - const RotationalInertiaRaw& getRotationalInertiaWrtFrameOrigin() const; - RotationalInertiaRaw getRotationalInertiaWrtCenterOfMass() const; - - - /** - * Function to combine the rigid body inertia of two different rigid bodies, - * giving the rigid body inertia of of the rigid body obtanined by welding the two bodies. - */ - static SpatialInertiaRaw combine(const SpatialInertiaRaw& op1, const SpatialInertiaRaw& op2); +#ifdef __DEPRECATED + #warning is deprecated. Please use . To disable this warning use -Wno-deprecated. +#endif - /** - * Multiplication function - * - */ - SpatialForceVector multiply(const SpatialMotionVector & op) const; +#include - /** reset to zero (i.e. the inertia of body with zero mass) the SpatialInertia */ - void zero(); - }; -} #endif diff --git a/src/core/src/SpatialInertia.cpp b/src/core/src/SpatialInertia.cpp index b79bbad083..2a0f5d9179 100644 --- a/src/core/src/SpatialInertia.cpp +++ b/src/core/src/SpatialInertia.cpp @@ -2,6 +2,7 @@ // SPDX-License-Identifier: BSD-3-Clause #include +#include #include #include #include @@ -19,29 +20,164 @@ namespace iDynTree { SpatialInertia::SpatialInertia(const double mass, - const PositionRaw& com, - const RotationalInertiaRaw& rotInertia): SpatialInertiaRaw(mass, com, rotInertia) + const Position& com, + const RotationalInertia& rotInertia): m_mass(mass), + m_rotInertia(rotInertia) { + for(int i = 0; i < 3; i++ ) + { + this->m_mcom[i] = this->m_mass*com(i); + } +} + +SpatialInertia::SpatialInertia(const SpatialInertia& other): m_mass(other.m_mass), + m_rotInertia(other.m_rotInertia) +{ + for(int i = 0; i < 3; i++ ) + { + m_mcom[i] = other.m_mcom[i]; + } +} + +void SpatialInertia::fromRotationalInertiaWrtCenterOfMass(const double mass, + const Position& com, + const RotationalInertia& rotInertiaWrtCom) +{ + this->m_mass = mass; + + for(int i = 0; i < 3; i++ ) + { + this->m_mcom[i] = this->m_mass*com(i); + } + + // Here we need to compute the rotational inertia at the com + // given the one expressed at the frame origin + // we apply formula 2.63 in Featherstone 2008 + Eigen::Map linkInertia(this->m_rotInertia.data()); + Eigen::Map comInertia(rotInertiaWrtCom.data()); + Eigen::Map mcom(this->m_mcom); + + if( fabs(this->m_mass) > 0) + { + linkInertia = comInertia - squareCrossProductMatrix(mcom)/this->m_mass; + } + else + { + linkInertia = comInertia; + } +} + + +double SpatialInertia::getMass() const +{ + return this->m_mass; +} + +Position SpatialInertia::getCenterOfMass() const +{ + Position ret; + + if( fabs(this->m_mass) > 0 ) + { + ret(0) = this->m_mcom[0]/this->m_mass; + ret(1) = this->m_mcom[1]/this->m_mass; + ret(2) = this->m_mcom[2]/this->m_mass; + } + else + { + ret.zero(); + } + + return ret; +} +const RotationalInertia& SpatialInertia::getRotationalInertiaWrtFrameOrigin() const +{ + return this->m_rotInertia; } -SpatialInertia::SpatialInertia(const SpatialInertiaRaw& other): SpatialInertiaRaw(other) +RotationalInertia SpatialInertia::getRotationalInertiaWrtCenterOfMass() const { + RotationalInertia retComInertia; + // Here we need to compute the rotational inertia at the com + // given the one expressed at the frame origin + // we apply formula 2.63 in Featherstone 2008 + Eigen::Map linkInertia(this->m_rotInertia.data()); + Eigen::Map comInertia(retComInertia.data()); + Eigen::Map mcom(this->m_mcom); + + if( fabs(this->m_mass) > 0 ) + { + comInertia = linkInertia + squareCrossProductMatrix(mcom)/this->m_mass; + } + else + { + comInertia = linkInertia; + } + return retComInertia; } +SpatialInertia SpatialInertia::combine(const SpatialInertia& op1, + const SpatialInertia& op2) +{ + SpatialInertia ret; + // If the two inertia are expressed with the same orientation + // and with respect to the same point (and this will be checked by + // the semantic check) we just need to sum + // the mass, the first moment of mass and the rotational inertia + ret.m_mass = op1.m_mass + op2.m_mass; + + Eigen::Map retMcom(ret.m_mcom); + Eigen::Map op1Mcom(op1.m_mcom); + Eigen::Map op2Mcom(op2.m_mcom); + + retMcom = op1Mcom + op2Mcom; + + Eigen::Map retRotInertia(ret.m_rotInertia.data()); + Eigen::Map op1RotInertia(op1.m_rotInertia.data()); + Eigen::Map op2RotInertia(op2.m_rotInertia.data()); -SpatialInertia::SpatialInertia(const SpatialInertia& other): SpatialInertiaRaw(other) + retRotInertia = op1RotInertia + op2RotInertia; + + return ret; +} + + +SpatialForceVector SpatialInertia::multiply(const SpatialMotionVector& op) const { + SpatialForceVector ret; + + // we call this linearForce and angularForce + // but please remember that they can also be + // linear and angular momentum + Eigen::Map linearForce(ret.getLinearVec3().data()); + Eigen::Map angularForce(ret.getAngularVec3().data()); + Eigen::Map linearMotion(op.getLinearVec3().data()); + Eigen::Map angularMotion(op.getAngularVec3().data()); + + Eigen::Map mcom(this->m_mcom); + Eigen::Map inertia3d(this->m_rotInertia.data()); + // Implementing the 2.63 formula in Featherstone 2008 + linearForce = this->m_mass*linearMotion - mcom.cross(angularMotion); + angularForce = mcom.cross(linearMotion) + inertia3d*(angularMotion); + + return ret; } -SpatialInertia SpatialInertia::combine(const SpatialInertia& op1, const SpatialInertia& op2) +void SpatialInertia::zero() { - return SpatialInertiaRaw::combine(op1,op2); + m_mass = 0.0; + for(int i = 0; i < 3; i++ ) + { + this->m_mcom[i] = 0.0; + } + this->m_rotInertia.zero(); } + // \todo TODO have a unique mySkew template inline Eigen::Matrix mySkewIn(const Eigen::MatrixBase & vec) @@ -103,18 +239,17 @@ SpatialInertia SpatialInertia::operator+(const SpatialInertia& other) const SpatialForceVector SpatialInertia::operator*(const SpatialMotionVector& other) const { - return SpatialInertiaRaw::multiply(other); + return SpatialInertia::multiply(other); } - Wrench SpatialInertia::operator*(const SpatialAcc& other) const { - return SpatialInertiaRaw::multiply(other); + return SpatialInertia::multiply(other); } SpatialMomentum SpatialInertia::operator*(const Twist& other) const { - return SpatialInertiaRaw::multiply(other); + return SpatialInertia::multiply(other); } Wrench SpatialInertia::biasWrench(const Twist& V) const @@ -223,7 +358,7 @@ bool SpatialInertia::isPhysicallyConsistent() const } // We get the inertia at the COM - RotationalInertiaRaw inertiaAtCOM = this->getRotationalInertiaWrtCenterOfMass(); + RotationalInertia inertiaAtCOM = this->getRotationalInertiaWrtCenterOfMass(); // We get the inertia at the principal axis using eigen SelfAdjointEigenSolver > eigenValuesSolver; diff --git a/src/core/src/SpatialInertiaRaw.cpp b/src/core/src/SpatialInertiaRaw.cpp deleted file mode 100644 index 489323771e..0000000000 --- a/src/core/src/SpatialInertiaRaw.cpp +++ /dev/null @@ -1,181 +0,0 @@ -// SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) -// SPDX-License-Identifier: BSD-3-Clause - - -#include -#include -#include -#include -#include -#include - -#include - -#include -#include - -#include - - -namespace iDynTree -{ -SpatialInertiaRaw::SpatialInertiaRaw(const double mass, - const PositionRaw& com, - const RotationalInertiaRaw& rotInertia): m_mass(mass), - m_rotInertia(rotInertia) -{ - for(int i = 0; i < 3; i++ ) - { - this->m_mcom[i] = this->m_mass*com(i); - } -} - -SpatialInertiaRaw::SpatialInertiaRaw(const SpatialInertiaRaw& other): m_mass(other.m_mass), - m_rotInertia(other.m_rotInertia) -{ - for(int i = 0; i < 3; i++ ) - { - m_mcom[i] = other.m_mcom[i]; - } -} - -void SpatialInertiaRaw::fromRotationalInertiaWrtCenterOfMass(const double mass, - const PositionRaw& com, - const RotationalInertiaRaw& rotInertiaWrtCom) -{ - this->m_mass = mass; - - for(int i = 0; i < 3; i++ ) - { - this->m_mcom[i] = this->m_mass*com(i); - } - - // Here we need to compute the rotational inertia at the com - // given the one expressed at the frame origin - // we apply formula 2.63 in Featherstone 2008 - Eigen::Map linkInertia(this->m_rotInertia.data()); - Eigen::Map comInertia(rotInertiaWrtCom.data()); - Eigen::Map mcom(this->m_mcom); - - if( fabs(this->m_mass) > 0) - { - linkInertia = comInertia - squareCrossProductMatrix(mcom)/this->m_mass; - } - else - { - linkInertia = comInertia; - } -} - - -double SpatialInertiaRaw::getMass() const -{ - return this->m_mass; -} - -PositionRaw SpatialInertiaRaw::getCenterOfMass() const -{ - PositionRaw ret; - - if( fabs(this->m_mass) > 0 ) - { - ret(0) = this->m_mcom[0]/this->m_mass; - ret(1) = this->m_mcom[1]/this->m_mass; - ret(2) = this->m_mcom[2]/this->m_mass; - } - else - { - ret.zero(); - } - - return ret; -} - -const RotationalInertiaRaw& SpatialInertiaRaw::getRotationalInertiaWrtFrameOrigin() const -{ - return this->m_rotInertia; -} - -RotationalInertiaRaw SpatialInertiaRaw::getRotationalInertiaWrtCenterOfMass() const -{ - RotationalInertiaRaw retComInertia; - // Here we need to compute the rotational inertia at the com - // given the one expressed at the frame origin - // we apply formula 2.63 in Featherstone 2008 - Eigen::Map linkInertia(this->m_rotInertia.data()); - Eigen::Map comInertia(retComInertia.data()); - Eigen::Map mcom(this->m_mcom); - - if( fabs(this->m_mass) > 0 ) - { - comInertia = linkInertia + squareCrossProductMatrix(mcom)/this->m_mass; - } - else - { - comInertia = linkInertia; - } - - return retComInertia; -} - -SpatialInertiaRaw SpatialInertiaRaw::combine(const SpatialInertiaRaw& op1, - const SpatialInertiaRaw& op2) -{ - SpatialInertiaRaw ret; - // If the two inertia are expressed with the same orientation - // and with respect to the same point (and this will be checked by - // the semantic check) we just need to sum - // the mass, the first moment of mass and the rotational inertia - ret.m_mass = op1.m_mass + op2.m_mass; - - Eigen::Map retMcom(ret.m_mcom); - Eigen::Map op1Mcom(op1.m_mcom); - Eigen::Map op2Mcom(op2.m_mcom); - - retMcom = op1Mcom + op2Mcom; - - Eigen::Map retRotInertia(ret.m_rotInertia.data()); - Eigen::Map op1RotInertia(op1.m_rotInertia.data()); - Eigen::Map op2RotInertia(op2.m_rotInertia.data()); - - retRotInertia = op1RotInertia + op2RotInertia; - - return ret; -} - - -SpatialForceVector SpatialInertiaRaw::multiply(const SpatialMotionVector& op) const -{ - SpatialForceVector ret; - - // we call this linearForce and angularForce - // but please remember that they can also be - // linear and angular momentum - Eigen::Map linearForce(ret.getLinearVec3().data()); - Eigen::Map angularForce(ret.getAngularVec3().data()); - Eigen::Map linearMotion(op.getLinearVec3().data()); - Eigen::Map angularMotion(op.getAngularVec3().data()); - - Eigen::Map mcom(this->m_mcom); - Eigen::Map inertia3d(this->m_rotInertia.data()); - - // Implementing the 2.63 formula in Featherstone 2008 - linearForce = this->m_mass*linearMotion - mcom.cross(angularMotion); - angularForce = mcom.cross(linearMotion) + inertia3d*(angularMotion); - - return ret; -} - - -void SpatialInertiaRaw::zero() -{ - m_mass = 0.0; - for(int i = 0; i < 3; i++ ) - { - this->m_mcom[i] = 0.0; - } - this->m_rotInertia.zero(); -} - - -} From 7efef72cae6f682bf9166705be4d1c7562b79b5b Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sun, 17 Sep 2023 15:34:30 +0200 Subject: [PATCH 5/8] Remove warnings related to Raw classes --- bindings/iDynTree.i | 11 ++---- bindings/pybind11/idyntree_core.cpp | 39 +++++++------------ bindings/python/python.i | 20 +++++----- src/core/include/iDynTree/Direction.h | 5 +++ src/core/include/iDynTree/Position.h | 5 +++ src/core/include/iDynTree/Rotation.h | 1 + src/core/include/iDynTree/RotationalInertia.h | 3 +- src/core/include/iDynTree/SpatialAcc.h | 1 + .../include/iDynTree/SpatialForceVector.h | 10 ++--- src/core/include/iDynTree/SpatialMomentum.h | 1 + .../include/iDynTree/SpatialMotionVector.h | 10 ++--- src/core/include/iDynTree/SpatialVector.h | 9 +++++ src/core/include/iDynTree/Twist.h | 1 + src/core/include/iDynTree/Wrench.h | 1 + src/core/src/ClassicalAcc.cpp | 4 +- src/core/src/Direction.cpp | 7 ++++ .../src/InertiaNonLinearParametrization.cpp | 4 +- src/core/src/Position.cpp | 8 ++++ src/core/src/Rotation.cpp | 9 +++++ src/core/src/RotationalInertia.cpp | 12 ++++++ src/core/src/SpatialAcc.cpp | 7 ++++ src/core/src/SpatialMomentum.cpp | 7 ++++ src/core/src/TestUtils.cpp | 2 +- src/core/src/Transform.cpp | 4 +- src/core/src/Twist.cpp | 8 ++++ src/core/src/Wrench.cpp | 7 ++++ .../tests/ArticulatedBodyInertiaUnitTest.cpp | 2 +- src/core/tests/SpatialInertiaUnitTest.cpp | 2 +- .../tests/TransformFromMatrix4x4UnitTest.cpp | 10 ++--- .../ExternalWrenchesEstimationUnitTest.cpp | 4 +- src/high-level/src/KinDynComputations.cpp | 6 +-- src/model/include/iDynTree/ModelTestUtils.h | 2 +- src/model/include/iDynTree/SubModel.h | 1 - src/model/src/DenavitHartenberg.cpp | 2 +- src/model/tests/LinkUnitTest.cpp | 2 +- src/model/tests/ModelUnitTest.cpp | 4 +- .../codecs/include/private/InertialElement.h | 2 +- src/model_io/codecs/src/InertialElement.cpp | 2 +- src/model_io/codecs/src/URDFModelExport.cpp | 2 +- .../InertialParametersSolidShapesHelpers.cpp | 4 +- .../DynamicsLinearizationIntegrationTest.cpp | 2 +- ...etersSolidShapesHelpersIntegrationTest.cpp | 2 +- 42 files changed, 158 insertions(+), 87 deletions(-) diff --git a/bindings/iDynTree.i b/bindings/iDynTree.i index bb14aaa404..c5446f8bd8 100644 --- a/bindings/iDynTree.i +++ b/bindings/iDynTree.i @@ -50,7 +50,6 @@ #include "iDynTree/VectorFixSize.h" // Basic Vectors: Point Vectors and Spatial Vectors -#include "iDynTree/PositionRaw.h" #include "iDynTree/Position.h" #include "iDynTree/SpatialForceVector.h" #include "iDynTree/SpatialMotionVector.h" @@ -63,14 +62,13 @@ #include "iDynTree/Axis.h" // Inertias -#include "iDynTree/RotationalInertiaRaw.h" -#include "iDynTree/SpatialInertiaRaw.h" +#include "iDynTree/RotationalInertia.h" +#include "iDynTree/SpatialInertia.h" #include "iDynTree/SpatialInertia.h" #include "iDynTree/ArticulatedBodyInertia.h" #include "iDynTree/InertiaNonLinearParametrization.h" // Transformations: Rotation and Transform -#include "iDynTree/RotationRaw.h" #include "iDynTree/Rotation.h" #include "iDynTree/Transform.h" #include "iDynTree/TransformDerivative.h" @@ -204,7 +202,6 @@ namespace std { %template(Vector16) iDynTree::VectorFixSize<16>; // Basic Vectors: Point Vectors and Spatial Vectors -%include "iDynTree/PositionRaw.h" %include "iDynTree/Position.h" %include "iDynTree/GeomVector3.h" @@ -236,14 +233,12 @@ namespace std { %include "iDynTree/Axis.h" // Inertias -%include "iDynTree/RotationalInertiaRaw.h" -%include "iDynTree/SpatialInertiaRaw.h" +%include "iDynTree/RotationalInertia.h" %include "iDynTree/SpatialInertia.h" %include "iDynTree/ArticulatedBodyInertia.h" %include "iDynTree/InertiaNonLinearParametrization.h" // Transformations: Rotation and Transform -%include "iDynTree/RotationRaw.h" %include "iDynTree/Rotation.h" %include "iDynTree/Transform.h" %include "iDynTree/TransformDerivative.h" diff --git a/bindings/pybind11/idyntree_core.cpp b/bindings/pybind11/idyntree_core.cpp index c48df152eb..277dde0df3 100644 --- a/bindings/pybind11/idyntree_core.cpp +++ b/bindings/pybind11/idyntree_core.cpp @@ -5,10 +5,8 @@ #include #include #include -#include #include -#include -#include +#include #include #include #include @@ -197,23 +195,17 @@ void iDynTreeCoreBindings(pybind11::module& module) { createFixSizeMatrix<6, 6>(module, "Matrix6x6"); // Positions, Rotations and Transforms. - py::class_>(module, "_PositionRaw") - // Do not expose constructor as we do not want users to use this class. - .def("__repr__", &PositionRaw::toString); - - py::class_(module, "Position") + py::class_>(module, "Position") .def(py::init()) .def(py::init()) .def(py::self + py::self) .def(py::self - py::self) .def(-py::self) + .def("__repr__", &Position::toString) .def_static("Zero", &Position::Zero); - py::class_>(module, "_RotationRaw") - // Do not expose constructor as we do not want users to use this class. - .def("__repr__", &RotationRaw::toString); - py::class_(module, "Rotation") + py::class_>(module, "Rotation") .def(py::init()) .def(py::init>(module, - "RotationalInertia") + py::class_>(module, + "RotationalInertia") .def(py::init()); - py::class_(module, "_SpatialInertiaRaw") + py::class_(module, "SpatialInertia") + .def(py::init()) + .def(py::init()) .def("from_rotational_inertia_wrt_center_of_mass", - &SpatialInertiaRaw::fromRotationalInertiaWrtCenterOfMass) - .def("get_mass", &SpatialInertiaRaw::getMass) - .def("get_center_of_mass", &SpatialInertiaRaw::getCenterOfMass) + &SpatialInertia::fromRotationalInertiaWrtCenterOfMass) + .def("get_mass", &SpatialInertia::getMass) + .def("get_center_of_mass", &SpatialInertia::getCenterOfMass) .def("get_rotational_inertia_wrt_frame_origin", - &SpatialInertiaRaw::getRotationalInertiaWrtFrameOrigin) + &SpatialInertia::getRotationalInertiaWrtFrameOrigin) .def("get_rotational_inertia_wrt_center_of_mass", - &SpatialInertiaRaw::getRotationalInertiaWrtCenterOfMass); - - py::class_(module, "SpatialInertia") - .def(py::init()) - .def(py::init()) + &SpatialInertia::getRotationalInertiaWrtCenterOfMass) .def_static("Zero", &SpatialInertia::Zero) .def("as_matrix", &SpatialInertia::asMatrix) .def(py::self + py::self) diff --git a/bindings/python/python.i b/bindings/python/python.i index 1e5033fec7..7cfa8beb8a 100644 --- a/bindings/python/python.i +++ b/bindings/python/python.i @@ -324,13 +324,13 @@ import_array(); if (i != 3 || j != 3) throw std::runtime_error("Wrong size of input matrix"); - return iDynTree::RotationRaw(in, static_cast(i), static_cast(j)); + return iDynTree::Rotation(in, static_cast(i), static_cast(j)); } Rotation(const double* in_data, const std::ptrdiff_t in_rows, const std::ptrdiff_t in_cols) { - iDynTree::Rotation* rot = new iDynTree::Rotation(iDynTree::RotationRaw(in_data, - static_cast(in_rows), - static_cast(in_cols))); + iDynTree::Rotation* rot = new iDynTree::Rotation(in_data, + static_cast(in_rows), + static_cast(in_cols)); return rot; } }; @@ -340,11 +340,11 @@ import_array(); if (size != 3) throw std::runtime_error("Wrong size of input array"); - return iDynTree::PositionRaw(in, static_cast(size)); + return iDynTree::Position(in, static_cast(size)); } Position(const double* in_data, const unsigned in_size) { - iDynTree::Position* pos = new iDynTree::Position(iDynTree::PositionRaw(in_data, in_size)); + iDynTree::Position* pos = new iDynTree::Position(in_data, in_size); return pos; } }; @@ -352,15 +352,15 @@ import_array(); %extend iDynTree::Transform { void setPosition(const double* in_data, const unsigned in_size) { - $self->setPosition(iDynTree::PositionRaw(in_data, static_cast(in_size))); + $self->setPosition(iDynTree::Position(in_data, static_cast(in_size))); } void setRotation(const double* in_data, const std::ptrdiff_t in_rows, const std::ptrdiff_t in_cols) { - $self->setRotation(iDynTree::RotationRaw(in_data, - static_cast(in_rows), - static_cast(in_cols))); + $self->setRotation(iDynTree::Rotation(in_data, + static_cast(in_rows), + static_cast(in_cols))); } }; diff --git a/src/core/include/iDynTree/Direction.h b/src/core/include/iDynTree/Direction.h index fb50593b57..d9d4dc7d9b 100644 --- a/src/core/include/iDynTree/Direction.h +++ b/src/core/include/iDynTree/Direction.h @@ -50,6 +50,11 @@ namespace iDynTree */ Direction(const double* in_data, const unsigned int in_size); + /** + * Assignment operator: assign a Direction from another Direction + */ + Direction& operator=(const Direction& other); + /** * Normalize the representation of the direction, useful if * the coordinates of the direction has been manually setted diff --git a/src/core/include/iDynTree/Position.h b/src/core/include/iDynTree/Position.h index df9a36f7b5..26ef89bde8 100644 --- a/src/core/include/iDynTree/Position.h +++ b/src/core/include/iDynTree/Position.h @@ -50,6 +50,11 @@ namespace iDynTree */ Position(const Position & other); + /** + * Assignment operator: assign a Position from another Position + */ + Position& operator=(const Position& other); + /** * Constructor from a raw buffer of 3 doubles. */ diff --git a/src/core/include/iDynTree/Rotation.h b/src/core/include/iDynTree/Rotation.h index 93d456586a..7e5ac268e2 100644 --- a/src/core/include/iDynTree/Rotation.h +++ b/src/core/include/iDynTree/Rotation.h @@ -110,6 +110,7 @@ namespace iDynTree /** * overloaded operators */ + Rotation& operator=(const Rotation & other); Rotation operator*(const Rotation & other) const; Rotation inverse() const; Position operator*(const Position & other) const; diff --git a/src/core/include/iDynTree/RotationalInertia.h b/src/core/include/iDynTree/RotationalInertia.h index 69f181ffbe..6d61490028 100644 --- a/src/core/include/iDynTree/RotationalInertia.h +++ b/src/core/include/iDynTree/RotationalInertia.h @@ -11,7 +11,7 @@ namespace iDynTree class Position; /** - * Class providing the raw coordinates for a 3d inertia matrix. + * Class providing the coordinates for a 3d inertia matrix. * * \ingroup iDynTreeCore * @@ -35,6 +35,7 @@ namespace iDynTree RotationalInertia(); RotationalInertia(const double * in_data, const unsigned int in_rows, const unsigned int in_cols); RotationalInertia(const RotationalInertia & other); + RotationalInertia& operator=(const RotationalInertia& other); /** * Initializer helper: return a zero matrix. diff --git a/src/core/include/iDynTree/SpatialAcc.h b/src/core/include/iDynTree/SpatialAcc.h index aa385b34ed..f7e10d9779 100644 --- a/src/core/include/iDynTree/SpatialAcc.h +++ b/src/core/include/iDynTree/SpatialAcc.h @@ -32,6 +32,7 @@ namespace iDynTree SpatialAcc(const SpatialAcc& other); // overloaded operator + SpatialAcc& operator=(const SpatialAcc &other); SpatialAcc operator+(const SpatialAcc &other) const; SpatialAcc operator-(const SpatialAcc &other) const; SpatialAcc operator-() const; diff --git a/src/core/include/iDynTree/SpatialForceVector.h b/src/core/include/iDynTree/SpatialForceVector.h index 318c085806..499cdce4ec 100644 --- a/src/core/include/iDynTree/SpatialForceVector.h +++ b/src/core/include/iDynTree/SpatialForceVector.h @@ -1,8 +1,8 @@ // SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) // SPDX-License-Identifier: BSD-3-Clause -#ifndef IDYNTREE_SPATIAL_FORCE_RAW_H -#define IDYNTREE_SPATIAL_FORCE_RAW_H +#ifndef IDYNTREE_SPATIAL_FORCE_VECTOR_H +#define IDYNTREE_SPATIAL_FORCE_VECTOR_H #include #include @@ -21,8 +21,8 @@ namespace iDynTree * * This is just a basic vector, used to implement the adjoint transformations in * a general way. The relative adjoint transformation is contained in - * TransformRaw::apply(SpatialForceRaw), - * for consistency with the iDynTree::PositionRaw class. + * Transform::apply(SpatialForce), + * for consistency with the iDynTree::Position class. * * \note in iDynTree, the spatial vector follows this serialization: the first three elements are * the linear part and the second three elements are the angular part. @@ -53,4 +53,4 @@ namespace iDynTree }; } -#endif /* IDYNTREE_SPATIAL_FORCE_RAW_H */ +#endif /* IDYNTREE_SPATIAL_FORCE_VECTOR_H */ diff --git a/src/core/include/iDynTree/SpatialMomentum.h b/src/core/include/iDynTree/SpatialMomentum.h index 4be7256352..25e42b7715 100644 --- a/src/core/include/iDynTree/SpatialMomentum.h +++ b/src/core/include/iDynTree/SpatialMomentum.h @@ -30,6 +30,7 @@ namespace iDynTree SpatialMomentum(const SpatialMomentum & other); // overloaded operators + SpatialMomentum& operator=(const SpatialMomentum &other); SpatialMomentum operator+(const SpatialMomentum &other) const; SpatialMomentum operator-(const SpatialMomentum &other) const; SpatialMomentum operator-() const; diff --git a/src/core/include/iDynTree/SpatialMotionVector.h b/src/core/include/iDynTree/SpatialMotionVector.h index 17147e66f6..8688465fec 100644 --- a/src/core/include/iDynTree/SpatialMotionVector.h +++ b/src/core/include/iDynTree/SpatialMotionVector.h @@ -1,8 +1,8 @@ // SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT) // SPDX-License-Identifier: BSD-3-Clause -#ifndef IDYNTREE_SPATIAL_MOTION_RAW_H -#define IDYNTREE_SPATIAL_MOTION_RAW_H +#ifndef IDYNTREE_SPATIAL_MOTION_VECTOR_H +#define IDYNTREE_SPATIAL_MOTION_VECTOR_H #include #include @@ -15,7 +15,7 @@ namespace iDynTree class Dummy {}; /** - * Class providing the raw coordinates for any motion spatial vector + * Class providing the coordinates for any motion spatial vector * (i.e. vector form of an element of se(3)). * * \ingroup iDynTreeCore @@ -28,8 +28,8 @@ namespace iDynTree * * This is just a basic vector, used to implement the adjoint transformations in * a general way. The relative adjoint transformation is contained in - * TransformRaw::apply(SpatialMotionRaw), - * for consistency with the iDynTree::PositionRaw class. + * Transform::apply(SpatialMotion), + * for consistency with the iDynTree::Position class. * * \note in iDynTree, the spatial vector follows this serialization: the first three elements are * the linear part and the second three elements are the angular part. diff --git a/src/core/include/iDynTree/SpatialVector.h b/src/core/include/iDynTree/SpatialVector.h index 32fe52c8e0..7cb39795e7 100644 --- a/src/core/include/iDynTree/SpatialVector.h +++ b/src/core/include/iDynTree/SpatialVector.h @@ -132,6 +132,7 @@ SpatialVector /** * overloaded operators */ + DerivedSpatialVecT& operator=(const DerivedSpatialVecT &other); DerivedSpatialVecT operator+(const DerivedSpatialVecT &other) const; DerivedSpatialVecT operator-(const DerivedSpatialVecT &other) const; DerivedSpatialVecT operator-() const; @@ -334,6 +335,14 @@ SpatialVector } // overloaded operators + SPATIALVECTOR_TEMPLATE_HDR + DerivedSpatialVecT& SPATIALVECTOR_INSTANCE_HDR::operator=(const DerivedSpatialVecT &other) + { + this->getLinearVec3() = other.getLinearVec3(); + this->getAngularVec3() = other.getAngularVec3(); + return &this; + } + SPATIALVECTOR_TEMPLATE_HDR DerivedSpatialVecT SPATIALVECTOR_INSTANCE_HDR::operator+(const DerivedSpatialVecT &other) const { diff --git a/src/core/include/iDynTree/Twist.h b/src/core/include/iDynTree/Twist.h index 251ca80caf..59820a176f 100644 --- a/src/core/include/iDynTree/Twist.h +++ b/src/core/include/iDynTree/Twist.h @@ -28,6 +28,7 @@ namespace iDynTree Twist(const Twist& other); /** overloaded operators **/ + Twist& operator=(const Twist & other); Twist operator+(const Twist &other) const; Twist operator-(const Twist &other) const; Twist operator-() const; diff --git a/src/core/include/iDynTree/Wrench.h b/src/core/include/iDynTree/Wrench.h index 4763f7a46d..2695b81143 100644 --- a/src/core/include/iDynTree/Wrench.h +++ b/src/core/include/iDynTree/Wrench.h @@ -23,6 +23,7 @@ namespace iDynTree Wrench(const Wrench & other); // overloaded operators + Wrench& operator=(const Wrench & other); Wrench operator+(const Wrench &other) const; Wrench operator-(const Wrench &other) const; Wrench operator-() const; diff --git a/src/core/src/ClassicalAcc.cpp b/src/core/src/ClassicalAcc.cpp index daa9f8993f..fd2333e4d0 100644 --- a/src/core/src/ClassicalAcc.cpp +++ b/src/core/src/ClassicalAcc.cpp @@ -4,7 +4,7 @@ #include #include #include -#include +#include #include @@ -29,7 +29,7 @@ ClassicalAcc::ClassicalAcc(const ClassicalAcc& other): } -const ClassicalAcc& ClassicalAcc::changeCoordFrame(const RotationRaw& newCoordFrame) +const ClassicalAcc& ClassicalAcc::changeCoordFrame(const Rotation& newCoordFrame) { Eigen::Map thisData(this->data()); Eigen::Map rotData(newCoordFrame.data()); diff --git a/src/core/src/Direction.cpp b/src/core/src/Direction.cpp index c0dd07b323..32f0ee1287 100644 --- a/src/core/src/Direction.cpp +++ b/src/core/src/Direction.cpp @@ -34,6 +34,13 @@ namespace iDynTree this->m_data[2] = other.m_data[2]; } + Direction& Direction::operator=(const Direction& other) + { + this->m_data[0] = other.m_data[0]; + this->m_data[1] = other.m_data[1]; + this->m_data[2] = other.m_data[2]; + return *this; + } void Direction::setToDefault() { diff --git a/src/core/src/InertiaNonLinearParametrization.cpp b/src/core/src/InertiaNonLinearParametrization.cpp index 1fa7584b0e..f319275592 100644 --- a/src/core/src/InertiaNonLinearParametrization.cpp +++ b/src/core/src/InertiaNonLinearParametrization.cpp @@ -126,7 +126,7 @@ void RigidBodyInertiaNonLinearParametrization::fromRigidBodyInertia(const Spatia this->com = inertia.getCenterOfMass(); // We get the inertia at the COM - RotationalInertiaRaw inertiaAtCOM = inertia.getRotationalInertiaWrtCenterOfMass(); + RotationalInertia inertiaAtCOM = inertia.getRotationalInertiaWrtCenterOfMass(); // We get the inertia at the principal axis using eigen JacobiSVD > eigenValuesSolver; @@ -163,7 +163,7 @@ void RigidBodyInertiaNonLinearParametrization::fromRigidBodyInertia(const Spatia SpatialInertia RigidBodyInertiaNonLinearParametrization::toRigidBodyInertia() const { // Compute the inertia wrt to the center of mass - RotationalInertiaRaw rotInertia; + RotationalInertia rotInertia; Eigen::Vector3d principalMomentOfInertiaAtCOM; diff --git a/src/core/src/Position.cpp b/src/core/src/Position.cpp index f2f5429562..33b222f727 100644 --- a/src/core/src/Position.cpp +++ b/src/core/src/Position.cpp @@ -68,6 +68,14 @@ namespace iDynTree } + Position& Position::operator=(const Position& other) + { + this->m_data[0] = other.m_data[0]; + this->m_data[1] = other.m_data[1]; + this->m_data[2] = other.m_data[2]; + return *this; + } + Position::Position(Span other): VectorFixSize< 3 >(other) { diff --git a/src/core/src/Rotation.cpp b/src/core/src/Rotation.cpp index 87557c55de..c576b46676 100644 --- a/src/core/src/Rotation.cpp +++ b/src/core/src/Rotation.cpp @@ -294,6 +294,15 @@ namespace iDynTree return inverse2(*this); } + Rotation& Rotation::operator=(const Rotation & other) + { + Eigen::Map thisData(m_data); + Eigen::Map otherData(other.data()); + thisData = otherData; + return *this; + } + + Rotation Rotation::operator*(const Rotation& other) const { return compose(*this,other); diff --git a/src/core/src/RotationalInertia.cpp b/src/core/src/RotationalInertia.cpp index 21bf51a32d..2744ea7d68 100644 --- a/src/core/src/RotationalInertia.cpp +++ b/src/core/src/RotationalInertia.cpp @@ -30,6 +30,18 @@ RotationalInertia::RotationalInertia(const RotationalInertia& other): Matrix3x3( { } +RotationalInertia& RotationalInertia::operator=(const RotationalInertia& other) +{ + for(std::size_t row=0; row < 3; row++ ) + { + for(std::size_t col=0; col < 3; col++ ) + { + this->m_data[row*3+col] = other.m_data[row*3+col]; + } + } + return *this; +} + RotationalInertia RotationalInertia::Zero() { RotationalInertia ret; diff --git a/src/core/src/SpatialAcc.cpp b/src/core/src/SpatialAcc.cpp index 36ac9b461d..7b821cead2 100644 --- a/src/core/src/SpatialAcc.cpp +++ b/src/core/src/SpatialAcc.cpp @@ -26,6 +26,13 @@ SpatialAcc::SpatialAcc(const SpatialAcc& other): } +SpatialAcc& SpatialAcc::operator=(const SpatialAcc &other) +{ + this->getLinearVec3() = other.getLinearVec3(); + this->getAngularVec3() = other.getAngularVec3(); + return *this; +} + SpatialAcc SpatialAcc::operator+(const SpatialAcc& other) const { return efficient6dSum(*this,other); diff --git a/src/core/src/SpatialMomentum.cpp b/src/core/src/SpatialMomentum.cpp index 175c355372..580164b1aa 100644 --- a/src/core/src/SpatialMomentum.cpp +++ b/src/core/src/SpatialMomentum.cpp @@ -26,6 +26,13 @@ SpatialMomentum::SpatialMomentum(const SpatialMomentum& other): } +SpatialMomentum& SpatialMomentum::operator=(const SpatialMomentum &other) +{ + this->getLinearVec3() = other.getLinearVec3(); + this->getAngularVec3() = other.getAngularVec3(); + return *this; +} + SpatialMomentum SpatialMomentum::operator+(const SpatialMomentum& other) const { return efficient6dSum(*this,other); diff --git a/src/core/src/TestUtils.cpp b/src/core/src/TestUtils.cpp index dc9221edd7..92b3de2b61 100644 --- a/src/core/src/TestUtils.cpp +++ b/src/core/src/TestUtils.cpp @@ -119,7 +119,7 @@ SpatialInertia getRandomInertia() SpatialInertia inertiaLink(getRandomDouble(0,4), Position(getRandomDouble(-2,2),getRandomDouble(-2,2),getRandomDouble(-2,2)), - rot*RotationalInertiaRaw(rotInertiaData,3,3)); + rot*RotationalInertia(rotInertiaData,3,3)); return inertiaLink; } diff --git a/src/core/src/Transform.cpp b/src/core/src/Transform.cpp index 119873ce8d..792e525581 100644 --- a/src/core/src/Transform.cpp +++ b/src/core/src/Transform.cpp @@ -329,9 +329,9 @@ std::string Transform::reservedToString() const // the rotational inertial is rotated and then // the parallel axis theorem applies - RotationalInertiaRaw newRotInertia; + RotationalInertia newRotInertia; Eigen::Map newI(newRotInertia.data()); - RotationalInertiaRaw oldRotInertiaWrtCom = op2.getRotationalInertiaWrtCenterOfMass(); + RotationalInertia oldRotInertiaWrtCom = op2.getRotationalInertiaWrtCenterOfMass(); Eigen::Map oldIWrtCom(oldRotInertiaWrtCom.data()); Eigen::Map R(op1.getRotation().data()); diff --git a/src/core/src/Twist.cpp b/src/core/src/Twist.cpp index 8d52d5203c..14c9595cf3 100644 --- a/src/core/src/Twist.cpp +++ b/src/core/src/Twist.cpp @@ -35,6 +35,14 @@ Twist::Twist(const Twist& other): } +Twist& Twist::operator=(const Twist &other) +{ + this->getLinearVec3() = other.getLinearVec3(); + this->getAngularVec3() = other.getAngularVec3(); + return *this; +} + + Twist Twist::operator+(const Twist& other) const { return efficient6dSum(*this,other); diff --git a/src/core/src/Wrench.cpp b/src/core/src/Wrench.cpp index 91d384d616..f9b1436e17 100644 --- a/src/core/src/Wrench.cpp +++ b/src/core/src/Wrench.cpp @@ -26,6 +26,13 @@ Wrench::Wrench(const Wrench& other): { } +Wrench& Wrench::operator=(const Wrench &other) +{ + this->getLinearVec3() = other.getLinearVec3(); + this->getAngularVec3() = other.getAngularVec3(); + return *this; +} + Wrench Wrench::operator+(const Wrench& other) const { return efficient6dSum(*this,other); diff --git a/src/core/tests/ArticulatedBodyInertiaUnitTest.cpp b/src/core/tests/ArticulatedBodyInertiaUnitTest.cpp index 82db735049..c511d4a8ff 100644 --- a/src/core/tests/ArticulatedBodyInertiaUnitTest.cpp +++ b/src/core/tests/ArticulatedBodyInertiaUnitTest.cpp @@ -125,7 +125,7 @@ int main() double rotInertiaData[3*3] = {10.0,0.5,0.8, 0.5,20.0,0.6, 0.8,0.6,25.0}; - SpatialInertia inertia(1.0,Position(0.3,0.6,0.2),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia inertia(1.0,Position(0.3,0.6,0.2),RotationalInertia(rotInertiaData,3,3)); ArticulatedBodyInertia abi = ArticulatedBodyInertia(inertia); checkInertiaAccProduct(abi,twist); diff --git a/src/core/tests/SpatialInertiaUnitTest.cpp b/src/core/tests/SpatialInertiaUnitTest.cpp index 3513816e14..ed9ed230f4 100644 --- a/src/core/tests/SpatialInertiaUnitTest.cpp +++ b/src/core/tests/SpatialInertiaUnitTest.cpp @@ -444,7 +444,7 @@ int main() double rotInertiaData[3*3] = {10.0,0.04,0.04, 0.04,20.0,0.04, 0.04,0.04,24.0}; - SpatialInertia inertia(1.0,Position(100,-5,10),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia inertia(1.0,Position(100,-5,10),RotationalInertia(rotInertiaData,3,3)); checkInertiaTwistProduct(inertia,twist); checkInertiaTransformation(trans,inertia); diff --git a/src/core/tests/TransformFromMatrix4x4UnitTest.cpp b/src/core/tests/TransformFromMatrix4x4UnitTest.cpp index 49b769c362..03f8af5188 100644 --- a/src/core/tests/TransformFromMatrix4x4UnitTest.cpp +++ b/src/core/tests/TransformFromMatrix4x4UnitTest.cpp @@ -15,13 +15,10 @@ using namespace iDynTree; void checkFromMatrix4x4() { - RotationRaw rot_raw(-2.449, -1.224, -2.041, 0.408, -0.707, -0.707, 0.816, 0.409, -1.154); - PositionRaw pos_raw(1, 2, 3); + Rotation rot(-2.449, -1.224, -2.041, 0.408, -0.707, -0.707, 0.816, 0.409, -1.154); + Position pos(1, 2, 3); double transform[16] = {-2.449, -1.224, -2.041, 1, 0.408, -0.707, -0.707, 2, 0.816, 0.409, -1.154, 3, 0, 0, 0, 1}; - Rotation rot = Rotation(rot_raw); - Position pos = Position(pos_raw); - Matrix4x4 homogeneousMatrix(transform, 4, 4); Transform t_posrot(rot, pos); @@ -32,9 +29,8 @@ void checkFromMatrix4x4() void checkLogExp() { - PositionRaw pos_raw(0, 0, 0); + Position pos(0, 0, 0); Rotation rot = Rotation::RPY(0.0, 1.57, 0.0); - Position pos = Position(pos_raw); Transform t_posrot(rot, pos); SpatialMotionVector v; diff --git a/src/estimation/tests/ExternalWrenchesEstimationUnitTest.cpp b/src/estimation/tests/ExternalWrenchesEstimationUnitTest.cpp index dfb791de9d..73f4326c14 100644 --- a/src/estimation/tests/ExternalWrenchesEstimationUnitTest.cpp +++ b/src/estimation/tests/ExternalWrenchesEstimationUnitTest.cpp @@ -37,7 +37,7 @@ inline Link getSimplestLink() SpatialInertia inertiaLink(7.0, Position(5.0,0.0,0.0), - rot*RotationalInertiaRaw(rotInertiaData,3,3)); + rot*RotationalInertia(rotInertiaData,3,3)); Link link; @@ -194,7 +194,7 @@ void checkSimpleModelExternalWrenchEstimationWithFTSensors() 0.0,1.0,0.0, 0.0,0.0,1.0}; - SpatialInertia inertia(1.0,iDynTree::Position::Zero(),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia inertia(1.0,iDynTree::Position::Zero(),RotationalInertia(rotInertiaData,3,3)); Link link0, link1, link2, link3; link0.setInertia(inertia); link1.setInertia(inertia); diff --git a/src/high-level/src/KinDynComputations.cpp b/src/high-level/src/KinDynComputations.cpp index 342c2d5735..6eda6cbaf8 100644 --- a/src/high-level/src/KinDynComputations.cpp +++ b/src/high-level/src/KinDynComputations.cpp @@ -2205,7 +2205,7 @@ void KinDynComputations::KinDynComputationsPrivateAttributes::processOnLeftSideB assert(jac.cols() == m_robot_model.getNrOfDOFs()+6); // Get the center of mass in the base frame - Position vectorFromComToBaseWithRotationOfBase = PositionRaw::inverse(this->getRobotLockedInertia().getCenterOfMass()); + Position vectorFromComToBaseWithRotationOfBase = Position::inverse(this->getRobotLockedInertia().getCenterOfMass()); Transform newOutputFrame_X_oldOutputFrame; if (leftSideRepresentation == BODY_FIXED_REPRESENTATION) @@ -2239,7 +2239,7 @@ Twist KinDynComputations::getCentroidalAverageVelocity() Twist base_averageVelocity = base_lockedInertia.applyInverse(base_momentum); // Get the center of mass in the base frame - Position vectorFromComToBaseWithRotationOfBase = PositionRaw::inverse(pimpl->getRobotLockedInertia().getCenterOfMass()); + Position vectorFromComToBaseWithRotationOfBase = Position::inverse(pimpl->getRobotLockedInertia().getCenterOfMass()); Transform newOutputFrame_X_oldOutputFrame; if (pimpl->m_frameVelRepr == BODY_FIXED_REPRESENTATION) @@ -2387,7 +2387,7 @@ SpatialMomentum KinDynComputations::getCentroidalTotalMomentum() SpatialMomentum base_momentum = pimpl->m_pos.worldBasePos().inverse()*pimpl->m_totalMomentum; // Get the center of mass in the base frame - Position vectorFromComToBaseWithRotationOfBase = PositionRaw::inverse(pimpl->getRobotLockedInertia().getCenterOfMass()); + Position vectorFromComToBaseWithRotationOfBase = Position::inverse(pimpl->getRobotLockedInertia().getCenterOfMass()); Transform newOutputFrame_X_oldOutputFrame; if (pimpl->m_frameVelRepr == BODY_FIXED_REPRESENTATION) diff --git a/src/model/include/iDynTree/ModelTestUtils.h b/src/model/include/iDynTree/ModelTestUtils.h index 9af0de0740..c1e092accf 100644 --- a/src/model/include/iDynTree/ModelTestUtils.h +++ b/src/model/include/iDynTree/ModelTestUtils.h @@ -33,7 +33,7 @@ inline Link getRandomLink() SpatialInertia inertiaLink(getRandomDouble(0,4), Position(getRandomDouble(-2,2),getRandomDouble(-2,2),getRandomDouble(-2,2)), - rot*RotationalInertiaRaw(rotInertiaData,3,3)); + rot*RotationalInertia(rotInertiaData,3,3)); Link link; diff --git a/src/model/include/iDynTree/SubModel.h b/src/model/include/iDynTree/SubModel.h index 6983428487..fc69adb4d3 100644 --- a/src/model/include/iDynTree/SubModel.h +++ b/src/model/include/iDynTree/SubModel.h @@ -16,7 +16,6 @@ namespace iDynTree class Traversal; class JointPosDoubleArray; class LinkPositions; - class IRawVector; /** * Class representing the decomposition in one model in several submodels. diff --git a/src/model/src/DenavitHartenberg.cpp b/src/model/src/DenavitHartenberg.cpp index f64d562c2c..5647bf8d05 100644 --- a/src/model/src/DenavitHartenberg.cpp +++ b/src/model/src/DenavitHartenberg.cpp @@ -738,7 +738,7 @@ bool CreateModelFromDHChain(const DHChain& inputChain, outputModel = Model(); // All the inertial will be of one kg in the origin - iDynTree::SpatialInertia inertiaDefault(1.0,Position::Zero(),RotationalInertiaRaw::Zero()); + iDynTree::SpatialInertia inertiaDefault(1.0,Position::Zero(),RotationalInertia::Zero()); iDynTree::Link linkDefault; linkDefault.setInertia(inertiaDefault); diff --git a/src/model/tests/LinkUnitTest.cpp b/src/model/tests/LinkUnitTest.cpp index fbf84d636c..573aad59b5 100644 --- a/src/model/tests/LinkUnitTest.cpp +++ b/src/model/tests/LinkUnitTest.cpp @@ -16,7 +16,7 @@ int main() double rotInertiaData[3*3] = {10.0,0.0,0.0, 0.0,20.0,0.0, 0.0,0.0,30.0}; - SpatialInertia settedInertia(1.0,Position(100,0,0),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia settedInertia(1.0,Position(100,0,0),RotationalInertia(rotInertiaData,3,3)); Link link; diff --git a/src/model/tests/ModelUnitTest.cpp b/src/model/tests/ModelUnitTest.cpp index a6a1283614..9b7d65e156 100644 --- a/src/model/tests/ModelUnitTest.cpp +++ b/src/model/tests/ModelUnitTest.cpp @@ -305,7 +305,7 @@ void checkSimpleModel() 0.0,12.0,0.0, 0.0,0.0,10.0}; - SpatialInertia inertiaLink0(1.0,Position(100,0,0),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia inertiaLink0(1.0,Position(100,0,0),RotationalInertia(rotInertiaData,3,3)); Link link0; link0.setInertia(inertiaLink0); @@ -354,7 +354,7 @@ void checkInsertJointAndLink() 0.0,12.0,0.0, 0.0,0.0,10.0}; - SpatialInertia inertiaLink0(1.0,Position(100,0,0),RotationalInertiaRaw(rotInertiaData,3,3)); + SpatialInertia inertiaLink0(1.0,Position(100,0,0),RotationalInertia(rotInertiaData,3,3)); Link link0; link0.setInertia(inertiaLink0); diff --git a/src/model_io/codecs/include/private/InertialElement.h b/src/model_io/codecs/include/private/InertialElement.h index 6ebce4dcb7..84bc6c890c 100644 --- a/src/model_io/codecs/include/private/InertialElement.h +++ b/src/model_io/codecs/include/private/InertialElement.h @@ -17,7 +17,7 @@ namespace iDynTree { class iDynTree::InertialElement: public iDynTree::XMLElement { Transform m_centerOfMass; double m_mass; - RotationalInertiaRaw m_rotationalInertiaWRTCoM; + RotationalInertia m_rotationalInertiaWRTCoM; iDynTree::Link &m_link; public: diff --git a/src/model_io/codecs/src/InertialElement.cpp b/src/model_io/codecs/src/InertialElement.cpp index 4d8f5a56c0..e2c6d732e8 100644 --- a/src/model_io/codecs/src/InertialElement.cpp +++ b/src/model_io/codecs/src/InertialElement.cpp @@ -79,7 +79,7 @@ namespace iDynTree { xy, yy, yz, xz, yz, zz }; - m_rotationalInertiaWRTCoM = RotationalInertiaRaw(buffer, 3, 3); + m_rotationalInertiaWRTCoM = RotationalInertia(buffer, 3, 3); return true; }); diff --git a/src/model_io/codecs/src/URDFModelExport.cpp b/src/model_io/codecs/src/URDFModelExport.cpp index c372933ea3..2637396f1e 100644 --- a/src/model_io/codecs/src/URDFModelExport.cpp +++ b/src/model_io/codecs/src/URDFModelExport.cpp @@ -89,7 +89,7 @@ bool exportInertial(const SpatialInertia &inertia, xmlNodePtr parent_element) ok = ok && exportTransform(Transform(Rotation::Identity(), inertia.getCenterOfMass()), inertial); xmlNodePtr inertia_xml = xmlNewChild(inertial, NULL, BAD_CAST "inertia", NULL); - RotationalInertiaRaw rotInertia = inertia.getRotationalInertiaWrtCenterOfMass(); + RotationalInertia rotInertia = inertia.getRotationalInertiaWrtCenterOfMass(); ok = ok && doubleToStringWithClassicLocale(rotInertia(0, 0), bufStr); xmlNewProp(inertia_xml, BAD_CAST "ixx", BAD_CAST bufStr.c_str()); ok = ok && doubleToStringWithClassicLocale(rotInertia(0, 1), bufStr); diff --git a/src/solid-shapes/src/InertialParametersSolidShapesHelpers.cpp b/src/solid-shapes/src/InertialParametersSolidShapesHelpers.cpp index f00922117a..a645ec585f 100644 --- a/src/solid-shapes/src/InertialParametersSolidShapesHelpers.cpp +++ b/src/solid-shapes/src/InertialParametersSolidShapesHelpers.cpp @@ -27,10 +27,10 @@ SpatialInertia boxGet6DInertiaInLinkFrameFromDensity(const Box& box, double boxVolume = box.getX() * box.getY() * box.getZ(); double boxMass = density*boxVolume; // Assuming uniform density, the center of mass is coincident with the box center - PositionRaw comInGeomFrame; + Position comInGeomFrame; comInGeomFrame.zero(); // From http://scienceworld.wolfram.com/physics/MomentofInertiaRectangularParallelepiped.html - RotationalInertiaRaw rotInertiaInGeomFrame; + RotationalInertia rotInertiaInGeomFrame; rotInertiaInGeomFrame.zero(); double x2 = box.getX() * box.getX(); double y2 = box.getY() * box.getY(); diff --git a/src/tests/integration/DynamicsLinearizationIntegrationTest.cpp b/src/tests/integration/DynamicsLinearizationIntegrationTest.cpp index 00416e9aae..0b6c6a3125 100644 --- a/src/tests/integration/DynamicsLinearizationIntegrationTest.cpp +++ b/src/tests/integration/DynamicsLinearizationIntegrationTest.cpp @@ -472,7 +472,7 @@ int main() // First test some models used for debug Model doubleBodyModel; - RotationalInertiaRaw rotInertia = RotationalInertiaRaw::Zero(); + RotationalInertia rotInertia = RotationalInertia::Zero(); rotInertia(0,0) = rotInertia(1,1) = rotInertia(2,2) = 1.0; Position com = Position::Zero(); diff --git a/src/tests/integration/InertialParametersSolidShapesHelpersIntegrationTest.cpp b/src/tests/integration/InertialParametersSolidShapesHelpersIntegrationTest.cpp index 629a21a9ba..bf4ea1fcf9 100644 --- a/src/tests/integration/InertialParametersSolidShapesHelpersIntegrationTest.cpp +++ b/src/tests/integration/InertialParametersSolidShapesHelpersIntegrationTest.cpp @@ -33,7 +33,7 @@ int main() // http://scienceworld.wolfram.com/physics/MomentofInertiaRectangularParallelepiped.html double totalMass = 24; double expectedInertia = 16; - RotationalInertiaRaw rotInertia; + RotationalInertia rotInertia; rotInertia.zero(); rotInertia(0, 0) = rotInertia(1, 1) = rotInertia(2, 2) = expectedInertia; From f4e2f20227490c96bd26d8e4f5d8570825f66a82 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sun, 17 Sep 2023 15:41:31 +0200 Subject: [PATCH 6/8] Update CHANGELOG.md --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index b51729b008..4bc57248d7 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -27,6 +27,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 - Linking `iDynTree::idyntree-sensors` is deprecated, you can just link `iDynTree::idyntree-model` instead, or just search and replace `iDynTree::idyntree-sensors` with an empty string if you are already linking `iDynTree::idyntree-model` (https://github.com/robotology/idyntree/pull/1104). - Including ``, ``, ``, ``, ``, `` is deprecated, just include `` . To perform this migration, just search and replace ` Date: Sat, 14 Oct 2023 17:49:48 +0200 Subject: [PATCH 7/8] update matlab bindings (#1121) Co-authored-by: traversaro --- .../autogenerated/+iDynTree/ACCELEROMETER.m | 2 +- .../+iDynTree/ACCELEROMETER_SENSOR.m | 2 +- .../+iDynTree/AccelerometerSensor.m | 30 +- .../+iDynTree/ArticulatedBodyAlgorithm.m | 2 +- .../ArticulatedBodyAlgorithmInternalBuffers.m | 44 +- .../+iDynTree/ArticulatedBodyInertia.m | 30 +- .../+iDynTree/AttitudeEstimatorState.m | 16 +- .../+iDynTree/AttitudeMahonyFilter.m | 40 +- .../AttitudeMahonyFilterParameters.m | 24 +- .../+iDynTree/AttitudeQuaternionEKF.m | 44 +- .../AttitudeQuaternionEKFParameters.m | 44 +- .../matlab/autogenerated/+iDynTree/Axis.m | 36 +- .../+iDynTree/BERDY_FLOATING_BASE.m | 2 +- ...LOATING_BASE_NON_COLLOCATED_EXT_WRENCHES.m | 2 +- .../+iDynTree/BODY_FIXED_REPRESENTATION.m | 2 +- .../+iDynTree/BerdyDynamicVariable.m | 20 +- .../+iDynTree/BerdyDynamicVariables.m | 50 +- .../autogenerated/+iDynTree/BerdyHelper.m | 66 +- .../autogenerated/+iDynTree/BerdyOptions.m | 38 +- .../autogenerated/+iDynTree/BerdySensor.m | 20 +- .../autogenerated/+iDynTree/BerdySensors.m | 50 +- .../+iDynTree/BerdySparseMAPSolver.m | 32 +- bindings/matlab/autogenerated/+iDynTree/Box.m | 18 +- .../autogenerated/+iDynTree/ClassicalAcc.m | 12 +- .../matlab/autogenerated/+iDynTree/ColorViz.m | 20 +- .../+iDynTree/CompositeRigidBodyAlgorithm.m | 2 +- .../ComputeLinearAndAngularMomentum.m | 2 +- ...teLinearAndAngularMomentumDerivativeBias.m | 2 +- .../autogenerated/+iDynTree/ContactWrench.m | 10 +- .../ConvexHullProjectionConstraint.m | 56 +- .../+iDynTree/CreateModelFromDHChain.m | 2 +- .../matlab/autogenerated/+iDynTree/Cylinder.m | 14 +- .../matlab/autogenerated/+iDynTree/DHChain.m | 26 +- .../matlab/autogenerated/+iDynTree/DHLink.m | 28 +- .../+iDynTree/DIRECTIONAL_LIGHT.m | 2 +- .../+iDynTree/DOFSpatialForceArray.m | 10 +- .../+iDynTree/DOFSpatialMotionArray.m | 10 +- .../+iDynTree/DOF_ACCELERATION.m | 2 +- .../+iDynTree/DOF_ACCELERATION_SENSOR.m | 2 +- .../+iDynTree/DOF_INVALID_INDEX.m | 4 +- .../+iDynTree/DOF_INVALID_NAME.m | 4 +- .../autogenerated/+iDynTree/DOF_TORQUE.m | 2 +- .../+iDynTree/DOF_TORQUE_SENSOR.m | 2 +- .../autogenerated/+iDynTree/Direction.m | 18 +- .../DiscreteExtendedKalmanFilterHelper.m | 40 +- .../matlab/autogenerated/+iDynTree/Dummy.m | 4 +- .../+iDynTree/DynamicMatrixView.m | 14 +- .../autogenerated/+iDynTree/DynamicSpan.m | 44 +- .../ExtWrenchesAndJointTorquesEstimator.m | 34 +- .../autogenerated/+iDynTree/ExternalMesh.m | 22 +- .../+iDynTree/ExtractDHChainFromModel.m | 2 +- .../+iDynTree/FRAME_INVALID_INDEX.m | 4 +- .../+iDynTree/FRAME_INVALID_NAME.m | 4 +- .../autogenerated/+iDynTree/FULL_WRENCH.m | 2 +- .../autogenerated/+iDynTree/FixedJoint.m | 80 +- .../+iDynTree/ForwardAccKinematics.m | 2 +- .../+iDynTree/ForwardBiasAccKinematics.m | 2 +- .../+iDynTree/ForwardPosVelAccKinematics.m | 2 +- .../+iDynTree/ForwardPosVelKinematics.m | 2 +- .../+iDynTree/ForwardPositionKinematics.m | 2 +- .../+iDynTree/ForwardVelAccKinematics.m | 2 +- .../+iDynTree/FrameFreeFloatingJacobian.m | 8 +- .../autogenerated/+iDynTree/FreeFloatingAcc.m | 12 +- .../FreeFloatingGeneralizedTorques.m | 12 +- .../+iDynTree/FreeFloatingMassMatrix.m | 6 +- .../autogenerated/+iDynTree/FreeFloatingPos.m | 12 +- .../autogenerated/+iDynTree/FreeFloatingVel.m | 12 +- .../autogenerated/+iDynTree/GYROSCOPE.m | 2 +- .../+iDynTree/GYROSCOPE_SENSOR.m | 2 +- .../autogenerated/+iDynTree/GeomVector3.m | 22 +- .../autogenerated/+iDynTree/GyroscopeSensor.m | 30 +- .../+iDynTree/IAttitudeEstimator.m | 22 +- .../matlab/autogenerated/+iDynTree/ICamera.m | 14 +- .../autogenerated/+iDynTree/ICameraAnimator.m | 16 +- .../autogenerated/+iDynTree/IEnvironment.m | 20 +- .../+iDynTree/IFrameVisualization.m | 14 +- .../+iDynTree/IJetsVisualization.m | 16 +- .../matlab/autogenerated/+iDynTree/IJoint.m | 90 +- .../matlab/autogenerated/+iDynTree/ILabel.m | 20 +- .../matlab/autogenerated/+iDynTree/ILight.m | 28 +- .../+iDynTree/IModelVisualization.m | 36 +- .../+iDynTree/INERTIAL_FIXED_REPRESENTATION.m | 2 +- .../matlab/autogenerated/+iDynTree/ITexture.m | 18 +- .../+iDynTree/ITexturesHandler.m | 6 +- .../+iDynTree/IVectorsVisualization.m | 22 +- .../autogenerated/+iDynTree/IndexRange.m | 16 +- .../autogenerated/+iDynTree/IndexVector.m | 95 + ...verseDynamicsInertialParametersRegressor.m | 2 +- .../+iDynTree/InverseKinematics.m | 118 +- ...ematicsRotationParametrizationQuaternion.m | 2 +- ...aticsRotationParametrizationRollPitchYaw.m | 2 +- ...rseKinematicsTreatTargetAsConstraintFull.m | 2 +- ...rseKinematicsTreatTargetAsConstraintNone.m | 2 +- ...aticsTreatTargetAsConstraintPositionOnly.m | 2 +- ...aticsTreatTargetAsConstraintRotationOnly.m | 2 +- .../+iDynTree/JOINT_INVALID_INDEX.m | 4 +- .../+iDynTree/JOINT_INVALID_NAME.m | 4 +- .../autogenerated/+iDynTree/JOINT_WRENCH.m | 2 +- .../+iDynTree/JOINT_WRENCH_SENSOR.m | 2 +- .../+iDynTree/JointDOFsDoubleArray.m | 8 +- .../+iDynTree/JointPosDoubleArray.m | 8 +- .../autogenerated/+iDynTree/JointSensor.m | 12 +- .../+iDynTree/KinDynComputations.m | 112 +- .../+iDynTree/LINK_BODY_PROPER_ACCELERATION.m | 2 +- .../LINK_BODY_PROPER_CLASSICAL_ACCELERATION.m | 2 +- .../+iDynTree/LINK_INVALID_INDEX.m | 4 +- .../+iDynTree/LINK_INVALID_NAME.m | 4 +- .../matlab/autogenerated/+iDynTree/Link.m | 14 +- .../autogenerated/+iDynTree/LinkAccArray.m | 14 +- .../+iDynTree/LinkArticulatedBodyInertias.m | 10 +- .../+iDynTree/LinkContactWrenches.m | 18 +- .../autogenerated/+iDynTree/LinkInertias.m | 10 +- .../autogenerated/+iDynTree/LinkPositions.m | 14 +- .../autogenerated/+iDynTree/LinkSensor.m | 16 +- .../+iDynTree/LinkUnknownWrenchContacts.m | 22 +- .../autogenerated/+iDynTree/LinkVelArray.m | 14 +- .../autogenerated/+iDynTree/LinkWrenches.m | 16 +- .../+iDynTree/LinksSolidShapesVector.m | 50 +- .../+iDynTree/MIXED_REPRESENTATION.m | 2 +- .../matlab/autogenerated/+iDynTree/Material.m | 18 +- .../autogenerated/+iDynTree/Matrix10x16.m | 30 +- .../autogenerated/+iDynTree/Matrix1x6.m | 30 +- .../autogenerated/+iDynTree/Matrix2x3.m | 30 +- .../autogenerated/+iDynTree/Matrix3x3.m | 30 +- .../autogenerated/+iDynTree/Matrix4x4.m | 30 +- .../autogenerated/+iDynTree/Matrix4x4Vector.m | 52 +- .../autogenerated/+iDynTree/Matrix6x10.m | 30 +- .../autogenerated/+iDynTree/Matrix6x6.m | 30 +- .../autogenerated/+iDynTree/MatrixDynSize.m | 38 +- .../+iDynTree/MatrixDynSizeVector.m | 95 + .../matlab/autogenerated/+iDynTree/Model.m | 94 +- .../+iDynTree/ModelCalibrationHelper.m | 18 +- .../autogenerated/+iDynTree/ModelExporter.m | 20 +- .../+iDynTree/ModelExporterOptions.m | 26 +- .../autogenerated/+iDynTree/ModelLoader.m | 24 +- .../+iDynTree/ModelParserOptions.m | 12 +- .../+iDynTree/ModelSolidShapes.m | 12 +- .../+iDynTree/MomentumFreeFloatingJacobian.m | 8 +- .../+iDynTree/MovableJointImpl1.m | 18 +- .../+iDynTree/MovableJointImpl2.m | 18 +- .../+iDynTree/MovableJointImpl3.m | 18 +- .../+iDynTree/MovableJointImpl4.m | 18 +- .../+iDynTree/MovableJointImpl5.m | 18 +- .../+iDynTree/MovableJointImpl6.m | 18 +- .../autogenerated/+iDynTree/NET_EXT_WRENCH.m | 2 +- .../+iDynTree/NET_EXT_WRENCH_SENSOR.m | 2 +- ...NT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV.m | 2 +- .../autogenerated/+iDynTree/NO_UNKNOWNS.m | 2 +- .../+iDynTree/NR_OF_SENSOR_TYPES.m | 2 +- .../matlab/autogenerated/+iDynTree/Neighbor.m | 12 +- .../autogenerated/+iDynTree/NoJointDynamics.m | 7 + .../+iDynTree/ORIGINAL_BERDY_FIXED_BASE.m | 2 +- .../autogenerated/+iDynTree/POINT_LIGHT.m | 2 +- .../autogenerated/+iDynTree/PURE_FORCE.m | 2 +- .../PURE_FORCE_WITH_KNOWN_DIRECTION.m | 2 +- .../matlab/autogenerated/+iDynTree/PixelViz.m | 12 +- .../matlab/autogenerated/+iDynTree/Polygon.m | 20 +- .../autogenerated/+iDynTree/Polygon2D.m | 16 +- .../matlab/autogenerated/+iDynTree/Position.m | 34 +- .../autogenerated/+iDynTree/PositionRaw.m | 45 - .../autogenerated/+iDynTree/PrismaticJoint.m | 68 +- .../autogenerated/+iDynTree/RCM_SENSOR.m | 2 +- .../+iDynTree/RNEADynamicPhase.m | 2 +- .../autogenerated/+iDynTree/RevoluteJoint.m | 68 +- ...RigidBodyInertiaNonLinearParametrization.m | 36 +- .../matlab/autogenerated/+iDynTree/Rotation.m | 72 +- .../autogenerated/+iDynTree/RotationRaw.m | 60 - ...tionalInertiaRaw.m => RotationalInertia.m} | 10 +- .../+iDynTree/SIX_AXIS_FORCE_TORQUE.m | 2 +- .../+iDynTree/SIX_AXIS_FORCE_TORQUE_SENSOR.m | 2 +- .../matlab/autogenerated/+iDynTree/Sensor.m | 16 +- .../autogenerated/+iDynTree/SensorsList.m | 34 +- .../+iDynTree/SensorsMeasurements.m | 18 +- .../+iDynTree/SimpleLeggedOdometry.m | 20 +- .../+iDynTree/SixAxisForceTorqueSensor.m | 58 +- .../autogenerated/+iDynTree/SolidShape.m | 36 +- .../+iDynTree/SolidShapesVector.m | 50 +- .../+iDynTree/SparseMatrixColMajor.m | 36 +- .../+iDynTree/SparseMatrixRowMajor.m | 36 +- .../autogenerated/+iDynTree/SpatialAcc.m | 10 +- .../+iDynTree/SpatialForceVector.m | 6 +- .../+iDynTree/SpatialForceVectorBase.m | 50 +- .../autogenerated/+iDynTree/SpatialInertia.m | 61 +- .../+iDynTree/SpatialInertiaRaw.m | 50 - .../autogenerated/+iDynTree/SpatialMomentum.m | 10 +- .../+iDynTree/SpatialMotionVector.m | 14 +- .../+iDynTree/SpatialMotionVectorBase.m | 50 +- .../matlab/autogenerated/+iDynTree/Sphere.m | 10 +- .../+iDynTree/SubModelDecomposition.m | 18 +- .../THREE_AXIS_ANGULAR_ACCELEROMETER.m | 2 +- .../THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR.m | 2 +- .../THREE_AXIS_FORCE_TORQUE_CONTACT.m | 2 +- .../THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR.m | 2 +- .../+iDynTree/TRAVERSAL_INVALID_INDEX.m | 4 +- .../ThreeAxisAngularAccelerometerSensor.m | 30 +- .../ThreeAxisForceTorqueContactSensor.m | 36 +- .../autogenerated/+iDynTree/Transform.m | 36 +- .../+iDynTree/TransformDerivative.m | 26 +- .../autogenerated/+iDynTree/TransformFromDH.m | 2 +- .../+iDynTree/TransformFromDHCraig1989.m | 2 +- .../autogenerated/+iDynTree/Traversal.m | 34 +- .../matlab/autogenerated/+iDynTree/Twist.m | 12 +- .../+iDynTree/URDFJointDynamics.m | 7 + .../+iDynTree/UnknownWrenchContact.m | 24 +- .../matlab/autogenerated/+iDynTree/Vector10.m | 36 +- .../matlab/autogenerated/+iDynTree/Vector16.m | 36 +- .../matlab/autogenerated/+iDynTree/Vector3.m | 36 +- .../matlab/autogenerated/+iDynTree/Vector4.m | 36 +- .../matlab/autogenerated/+iDynTree/Vector6.m | 36 +- .../autogenerated/+iDynTree/VectorDynSize.m | 44 +- .../+iDynTree/VectorDynSizeVector.m | 95 + .../autogenerated/+iDynTree/Visualizer.m | 48 +- .../+iDynTree/VisualizerOptions.m | 20 +- .../matlab/autogenerated/+iDynTree/Wrench.m | 10 +- .../addRandomAdditionalFrameToModel.m | 2 +- .../+iDynTree/addRandomLinkToModel.m | 2 +- .../+iDynTree/checkDoublesAreEqual.m | 2 +- .../+iDynTree/computeBoundingBoxFromShape.m | 2 +- .../+iDynTree/computeBoxVertices.m | 2 +- .../computeLinkNetWrenchesWithoutGravity.m | 2 +- .../computeTransformToSubModelBase.m | 2 +- .../computeTransformToTraversalBase.m | 2 +- .../createModelWithNormalizedJointNumbering.m | 2 +- .../+iDynTree/createReducedModel.m | 2 +- .../+iDynTree/dofsListFromURDF.m | 2 +- .../+iDynTree/dofsListFromURDFString.m | 2 +- .../autogenerated/+iDynTree/dynamic_extent.m | 2 +- ...ynamicsEstimationForwardVelAccKinematics.m | 2 +- .../dynamicsEstimationForwardVelKinematics.m | 2 +- .../+iDynTree/estimateExternalWrenches.m | 2 +- .../estimateExternalWrenchesBuffers.m | 32 +- ...stimateExternalWrenchesWithoutInternalFT.m | 2 +- ...ametersFromLinkBoundingBoxesAndTotalMass.m | 2 +- ...ntactWrenchesFromLinkNetExternalWrenches.m | 2 +- .../autogenerated/+iDynTree/extractSubModel.m | 2 +- .../autogenerated/+iDynTree/getRandomChain.m | 2 +- .../getRandomInverseDynamicsInputs.m | 2 +- .../+iDynTree/getRandomJointPositions.m | 2 +- .../autogenerated/+iDynTree/getRandomLink.m | 2 +- .../+iDynTree/getRandomLinkIndexOfModel.m | 2 +- .../+iDynTree/getRandomLinkOfModel.m | 2 +- .../autogenerated/+iDynTree/getRandomModel.m | 2 +- .../+iDynTree/getSensorTypeSize.m | 2 +- .../+iDynTree/input_dimensions.m | 2 +- .../autogenerated/+iDynTree/int2string.m | 2 +- .../+iDynTree/isDOFBerdyDynamicVariable.m | 2 +- .../+iDynTree/isJointBerdyDynamicVariable.m | 2 +- .../autogenerated/+iDynTree/isJointSensor.m | 2 +- .../+iDynTree/isLinkBerdyDynamicVariable.m | 2 +- .../autogenerated/+iDynTree/isLinkSensor.m | 2 +- .../output_dimensions_with_magnetometer.m | 2 +- .../output_dimensions_without_magnetometer.m | 2 +- .../+iDynTree/predictSensorsMeasurements.m | 2 +- ...predictSensorsMeasurementsFromRawBuffers.m | 2 +- .../autogenerated/+iDynTree/removeFakeLinks.m | 2 +- .../autogenerated/+iDynTree/reportDebug.m | 2 +- .../autogenerated/+iDynTree/reportInfo.m | 2 +- .../+iDynTree/sizeOfRotationParametrization.m | 2 +- .../autogenerated/iDynTreeMATLAB_wrap.cxx | 73751 ++++++++-------- 259 files changed, 41619 insertions(+), 36827 deletions(-) create mode 100644 bindings/matlab/autogenerated/+iDynTree/IndexVector.m create mode 100644 bindings/matlab/autogenerated/+iDynTree/MatrixDynSizeVector.m create mode 100644 bindings/matlab/autogenerated/+iDynTree/NoJointDynamics.m delete mode 100644 bindings/matlab/autogenerated/+iDynTree/PositionRaw.m delete mode 100644 bindings/matlab/autogenerated/+iDynTree/RotationRaw.m rename bindings/matlab/autogenerated/+iDynTree/{RotationalInertiaRaw.m => RotationalInertia.m} (66%) delete mode 100644 bindings/matlab/autogenerated/+iDynTree/SpatialInertiaRaw.m create mode 100644 bindings/matlab/autogenerated/+iDynTree/URDFJointDynamics.m create mode 100644 bindings/matlab/autogenerated/+iDynTree/VectorDynSizeVector.m diff --git a/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER.m b/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER.m index 7b80824cc7..0428171e6e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER.m +++ b/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER.m @@ -1,7 +1,7 @@ function v = ACCELEROMETER() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 6); + vInitialized = iDynTreeMEX(0, 5); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER_SENSOR.m index 5b55d79d40..6bf8b25b39 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/ACCELEROMETER_SENSOR.m @@ -1,7 +1,7 @@ function v = ACCELEROMETER_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 25); + vInitialized = iDynTreeMEX(0, 27); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/AccelerometerSensor.m b/bindings/matlab/autogenerated/+iDynTree/AccelerometerSensor.m index 99b51a395f..1623f7bd3f 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AccelerometerSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/AccelerometerSensor.m @@ -7,55 +7,55 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1376, varargin{:}); + tmp = iDynTreeMEX(1340, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1377, self); + iDynTreeMEX(1341, self); self.SwigClear(); end end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1378, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1342, self, varargin{:}); end function varargout = setLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1379, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1343, self, varargin{:}); end function varargout = setParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1380, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1344, self, varargin{:}); end function varargout = setParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1381, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1345, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1382, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1346, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1383, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1347, self, varargin{:}); end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1384, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1348, self, varargin{:}); end function varargout = getParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1385, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1349, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1386, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1350, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1387, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1351, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1388, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1352, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1389, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1353, self, varargin{:}); end function varargout = predictMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1390, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1354, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithm.m b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithm.m index 5ee93a029f..6f3c59605b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithm.m +++ b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithm.m @@ -1,3 +1,3 @@ function varargout = ArticulatedBodyAlgorithm(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1262, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1487, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithmInternalBuffers.m b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithmInternalBuffers.m index 981586e6da..759a2688ea 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithmInternalBuffers.m +++ b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyAlgorithmInternalBuffers.m @@ -9,110 +9,110 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1240, varargin{:}); + tmp = iDynTreeMEX(1465, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1241, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1466, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1242, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1467, self, varargin{:}); end function varargout = S(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1243, self); + varargout{1} = iDynTreeMEX(1468, self); else nargoutchk(0, 0) - iDynTreeMEX(1244, self, varargin{1}); + iDynTreeMEX(1469, self, varargin{1}); end end function varargout = U(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1245, self); + varargout{1} = iDynTreeMEX(1470, self); else nargoutchk(0, 0) - iDynTreeMEX(1246, self, varargin{1}); + iDynTreeMEX(1471, self, varargin{1}); end end function varargout = D(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1247, self); + varargout{1} = iDynTreeMEX(1472, self); else nargoutchk(0, 0) - iDynTreeMEX(1248, self, varargin{1}); + iDynTreeMEX(1473, self, varargin{1}); end end function varargout = u(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1249, self); + varargout{1} = iDynTreeMEX(1474, self); else nargoutchk(0, 0) - iDynTreeMEX(1250, self, varargin{1}); + iDynTreeMEX(1475, self, varargin{1}); end end function varargout = linksVel(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1251, self); + varargout{1} = iDynTreeMEX(1476, self); else nargoutchk(0, 0) - iDynTreeMEX(1252, self, varargin{1}); + iDynTreeMEX(1477, self, varargin{1}); end end function varargout = linksBiasAcceleration(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1253, self); + varargout{1} = iDynTreeMEX(1478, self); else nargoutchk(0, 0) - iDynTreeMEX(1254, self, varargin{1}); + iDynTreeMEX(1479, self, varargin{1}); end end function varargout = linksAccelerations(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1255, self); + varargout{1} = iDynTreeMEX(1480, self); else nargoutchk(0, 0) - iDynTreeMEX(1256, self, varargin{1}); + iDynTreeMEX(1481, self, varargin{1}); end end function varargout = linkABIs(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1257, self); + varargout{1} = iDynTreeMEX(1482, self); else nargoutchk(0, 0) - iDynTreeMEX(1258, self, varargin{1}); + iDynTreeMEX(1483, self, varargin{1}); end end function varargout = linksBiasWrench(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1259, self); + varargout{1} = iDynTreeMEX(1484, self); else nargoutchk(0, 0) - iDynTreeMEX(1260, self, varargin{1}); + iDynTreeMEX(1485, self, varargin{1}); end end function delete(self) if self.swigPtr - iDynTreeMEX(1261, self); + iDynTreeMEX(1486, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyInertia.m b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyInertia.m index e8e0bab827..6d437b7977 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyInertia.m +++ b/bindings/matlab/autogenerated/+iDynTree/ArticulatedBodyInertia.m @@ -9,57 +9,57 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(585, varargin{:}); + tmp = iDynTreeMEX(648, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = getLinearLinearSubmatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(586, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(649, self, varargin{:}); end function varargout = getLinearAngularSubmatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(587, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(650, self, varargin{:}); end function varargout = getAngularAngularSubmatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(588, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(651, self, varargin{:}); end function varargout = applyInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(590, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(653, self, varargin{:}); end function varargout = asMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(591, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(654, self, varargin{:}); end function varargout = getInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(592, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(655, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(593, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(656, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(594, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(657, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(595, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(658, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(596, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(659, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(599, self); + iDynTreeMEX(662, self); self.SwigClear(); end end end methods(Static) function varargout = combine(varargin) - [varargout{1:nargout}] = iDynTreeMEX(589, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(652, varargin{:}); end function varargout = ABADyadHelper(varargin) - [varargout{1:nargout}] = iDynTreeMEX(597, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(660, varargin{:}); end function varargout = ABADyadHelperLin(varargin) - [varargout{1:nargout}] = iDynTreeMEX(598, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(661, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/AttitudeEstimatorState.m b/bindings/matlab/autogenerated/+iDynTree/AttitudeEstimatorState.m index 407b59ed44..f83095f22d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AttitudeEstimatorState.m +++ b/bindings/matlab/autogenerated/+iDynTree/AttitudeEstimatorState.m @@ -7,30 +7,30 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1648, self); + varargout{1} = iDynTreeMEX(1731, self); else nargoutchk(0, 0) - iDynTreeMEX(1649, self, varargin{1}); + iDynTreeMEX(1732, self, varargin{1}); end end function varargout = m_angular_velocity(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1650, self); + varargout{1} = iDynTreeMEX(1733, self); else nargoutchk(0, 0) - iDynTreeMEX(1651, self, varargin{1}); + iDynTreeMEX(1734, self, varargin{1}); end end function varargout = m_gyroscope_bias(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1652, self); + varargout{1} = iDynTreeMEX(1735, self); else nargoutchk(0, 0) - iDynTreeMEX(1653, self, varargin{1}); + iDynTreeMEX(1736, self, varargin{1}); end end function self = AttitudeEstimatorState(varargin) @@ -39,14 +39,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1654, varargin{:}); + tmp = iDynTreeMEX(1737, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1655, self); + iDynTreeMEX(1738, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilter.m b/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilter.m index 670b3f41aa..9f14d7d256 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilter.m +++ b/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilter.m @@ -7,68 +7,68 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1679, varargin{:}); + tmp = iDynTreeMEX(1762, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = useMagnetoMeterMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1680, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1763, self, varargin{:}); end function varargout = setConfidenceForMagnetometerMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1681, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1764, self, varargin{:}); end function varargout = setGainkp(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1682, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1765, self, varargin{:}); end function varargout = setGainki(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1683, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1766, self, varargin{:}); end function varargout = setTimeStepInSeconds(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1684, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1767, self, varargin{:}); end function varargout = setGravityDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1685, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1768, self, varargin{:}); end function varargout = setParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1686, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1769, self, varargin{:}); end function varargout = getParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1687, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1770, self, varargin{:}); end function varargout = updateFilterWithMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1688, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1771, self, varargin{:}); end function varargout = propagateStates(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1689, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1772, self, varargin{:}); end function varargout = getOrientationEstimateAsRotationMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1690, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1773, self, varargin{:}); end function varargout = getOrientationEstimateAsQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1691, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1774, self, varargin{:}); end function varargout = getOrientationEstimateAsRPY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1692, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1775, self, varargin{:}); end function varargout = getInternalStateSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1693, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1776, self, varargin{:}); end function varargout = getInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1694, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1777, self, varargin{:}); end function varargout = getDefaultInternalInitialState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1695, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1778, self, varargin{:}); end function varargout = setInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1696, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1779, self, varargin{:}); end function varargout = setInternalStateInitialOrientation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1697, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1780, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1698, self); + iDynTreeMEX(1781, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilterParameters.m b/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilterParameters.m index 502a6f2a0d..099cf7b043 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilterParameters.m +++ b/bindings/matlab/autogenerated/+iDynTree/AttitudeMahonyFilterParameters.m @@ -7,50 +7,50 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1667, self); + varargout{1} = iDynTreeMEX(1750, self); else nargoutchk(0, 0) - iDynTreeMEX(1668, self, varargin{1}); + iDynTreeMEX(1751, self, varargin{1}); end end function varargout = kp(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1669, self); + varargout{1} = iDynTreeMEX(1752, self); else nargoutchk(0, 0) - iDynTreeMEX(1670, self, varargin{1}); + iDynTreeMEX(1753, self, varargin{1}); end end function varargout = ki(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1671, self); + varargout{1} = iDynTreeMEX(1754, self); else nargoutchk(0, 0) - iDynTreeMEX(1672, self, varargin{1}); + iDynTreeMEX(1755, self, varargin{1}); end end function varargout = use_magnetometer_measurements(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1673, self); + varargout{1} = iDynTreeMEX(1756, self); else nargoutchk(0, 0) - iDynTreeMEX(1674, self, varargin{1}); + iDynTreeMEX(1757, self, varargin{1}); end end function varargout = confidence_magnetometer_measurements(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1675, self); + varargout{1} = iDynTreeMEX(1758, self); else nargoutchk(0, 0) - iDynTreeMEX(1676, self, varargin{1}); + iDynTreeMEX(1759, self, varargin{1}); end end function self = AttitudeMahonyFilterParameters(varargin) @@ -59,14 +59,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1677, varargin{:}); + tmp = iDynTreeMEX(1760, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1678, self); + iDynTreeMEX(1761, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKF.m b/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKF.m index 0d4e318de4..aef9201a6c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKF.m +++ b/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKF.m @@ -11,74 +11,74 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1744, varargin{:}); + tmp = iDynTreeMEX(1827, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = getParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1745, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1828, self, varargin{:}); end function varargout = setParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1746, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1829, self, varargin{:}); end function varargout = setGravityDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1747, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1830, self, varargin{:}); end function varargout = setTimeStepInSeconds(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1748, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1831, self, varargin{:}); end function varargout = setBiasCorrelationTimeFactor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1749, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1832, self, varargin{:}); end function varargout = useMagnetometerMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1750, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1833, self, varargin{:}); end function varargout = setMeasurementNoiseVariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1751, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1834, self, varargin{:}); end function varargout = setSystemNoiseVariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1752, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1835, self, varargin{:}); end function varargout = setInitialStateCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1753, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1836, self, varargin{:}); end function varargout = initializeFilter(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1754, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1837, self, varargin{:}); end function varargout = updateFilterWithMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1755, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1838, self, varargin{:}); end function varargout = propagateStates(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1756, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1839, self, varargin{:}); end function varargout = getOrientationEstimateAsRotationMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1757, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1840, self, varargin{:}); end function varargout = getOrientationEstimateAsQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1758, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1841, self, varargin{:}); end function varargout = getOrientationEstimateAsRPY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1759, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1842, self, varargin{:}); end function varargout = getInternalStateSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1760, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1843, self, varargin{:}); end function varargout = getInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1761, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1844, self, varargin{:}); end function varargout = getDefaultInternalInitialState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1762, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1845, self, varargin{:}); end function varargout = setInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1763, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1846, self, varargin{:}); end function varargout = setInternalStateInitialOrientation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1764, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1847, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1765, self); + iDynTreeMEX(1848, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKFParameters.m b/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKFParameters.m index d7a6113d4b..35377ee369 100644 --- a/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKFParameters.m +++ b/bindings/matlab/autogenerated/+iDynTree/AttitudeQuaternionEKFParameters.m @@ -7,100 +7,100 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1722, self); + varargout{1} = iDynTreeMEX(1805, self); else nargoutchk(0, 0) - iDynTreeMEX(1723, self, varargin{1}); + iDynTreeMEX(1806, self, varargin{1}); end end function varargout = bias_correlation_time_factor(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1724, self); + varargout{1} = iDynTreeMEX(1807, self); else nargoutchk(0, 0) - iDynTreeMEX(1725, self, varargin{1}); + iDynTreeMEX(1808, self, varargin{1}); end end function varargout = accelerometer_noise_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1726, self); + varargout{1} = iDynTreeMEX(1809, self); else nargoutchk(0, 0) - iDynTreeMEX(1727, self, varargin{1}); + iDynTreeMEX(1810, self, varargin{1}); end end function varargout = magnetometer_noise_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1728, self); + varargout{1} = iDynTreeMEX(1811, self); else nargoutchk(0, 0) - iDynTreeMEX(1729, self, varargin{1}); + iDynTreeMEX(1812, self, varargin{1}); end end function varargout = gyroscope_noise_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1730, self); + varargout{1} = iDynTreeMEX(1813, self); else nargoutchk(0, 0) - iDynTreeMEX(1731, self, varargin{1}); + iDynTreeMEX(1814, self, varargin{1}); end end function varargout = gyro_bias_noise_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1732, self); + varargout{1} = iDynTreeMEX(1815, self); else nargoutchk(0, 0) - iDynTreeMEX(1733, self, varargin{1}); + iDynTreeMEX(1816, self, varargin{1}); end end function varargout = initial_orientation_error_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1734, self); + varargout{1} = iDynTreeMEX(1817, self); else nargoutchk(0, 0) - iDynTreeMEX(1735, self, varargin{1}); + iDynTreeMEX(1818, self, varargin{1}); end end function varargout = initial_ang_vel_error_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1736, self); + varargout{1} = iDynTreeMEX(1819, self); else nargoutchk(0, 0) - iDynTreeMEX(1737, self, varargin{1}); + iDynTreeMEX(1820, self, varargin{1}); end end function varargout = initial_gyro_bias_error_variance(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1738, self); + varargout{1} = iDynTreeMEX(1821, self); else nargoutchk(0, 0) - iDynTreeMEX(1739, self, varargin{1}); + iDynTreeMEX(1822, self, varargin{1}); end end function varargout = use_magnetometer_measurements(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1740, self); + varargout{1} = iDynTreeMEX(1823, self); else nargoutchk(0, 0) - iDynTreeMEX(1741, self, varargin{1}); + iDynTreeMEX(1824, self, varargin{1}); end end function self = AttitudeQuaternionEKFParameters(varargin) @@ -109,14 +109,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1742, varargin{:}); + tmp = iDynTreeMEX(1825, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1743, self); + iDynTreeMEX(1826, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Axis.m b/bindings/matlab/autogenerated/+iDynTree/Axis.m index b66797bec4..ef4b3ecb05 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Axis.m +++ b/bindings/matlab/autogenerated/+iDynTree/Axis.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(537, varargin{:}); + tmp = iDynTreeMEX(603, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = getDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(538, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(604, self, varargin{:}); end function varargout = getOrigin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(539, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(605, self, varargin{:}); end function varargout = setDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(540, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(606, self, varargin{:}); end function varargout = setOrigin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(541, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(607, self, varargin{:}); end function varargout = getRotationTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(542, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(608, self, varargin{:}); end function varargout = getRotationTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(543, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(609, self, varargin{:}); end function varargout = getRotationTwist(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(544, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(610, self, varargin{:}); end function varargout = getRotationSpatialAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(545, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(611, self, varargin{:}); end function varargout = getTranslationTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(546, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(612, self, varargin{:}); end function varargout = getTranslationTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(547, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(613, self, varargin{:}); end function varargout = getTranslationTwist(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(548, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(614, self, varargin{:}); end function varargout = getTranslationSpatialAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(549, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(615, self, varargin{:}); end function varargout = isParallel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(550, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(616, self, varargin{:}); end function varargout = reverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(551, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(617, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(552, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(618, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(553, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(619, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(554, self); + iDynTreeMEX(620, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE.m b/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE.m index e3970cd06b..ddad339fe6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE.m +++ b/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE.m @@ -1,7 +1,7 @@ function v = BERDY_FLOATING_BASE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 15); + vInitialized = iDynTreeMEX(0, 17); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES.m b/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES.m index a588864c64..16483ab10a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES.m +++ b/bindings/matlab/autogenerated/+iDynTree/BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES.m @@ -1,7 +1,7 @@ function v = BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 16); + vInitialized = iDynTreeMEX(0, 18); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/BODY_FIXED_REPRESENTATION.m b/bindings/matlab/autogenerated/+iDynTree/BODY_FIXED_REPRESENTATION.m index 4d598f49fe..b6c4aad2e8 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BODY_FIXED_REPRESENTATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/BODY_FIXED_REPRESENTATION.m @@ -1,7 +1,7 @@ function v = BODY_FIXED_REPRESENTATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 3); + vInitialized = iDynTreeMEX(0, 10); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariable.m b/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariable.m index f964c27f98..aa85fec7a2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariable.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariable.m @@ -7,37 +7,37 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1589, self); + varargout{1} = iDynTreeMEX(1672, self); else nargoutchk(0, 0) - iDynTreeMEX(1590, self, varargin{1}); + iDynTreeMEX(1673, self, varargin{1}); end end function varargout = id(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1591, self); + varargout{1} = iDynTreeMEX(1674, self); else nargoutchk(0, 0) - iDynTreeMEX(1592, self, varargin{1}); + iDynTreeMEX(1675, self, varargin{1}); end end function varargout = range(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1593, self); + varargout{1} = iDynTreeMEX(1676, self); else nargoutchk(0, 0) - iDynTreeMEX(1594, self, varargin{1}); + iDynTreeMEX(1677, self, varargin{1}); end end function varargout = eq(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1595, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1678, self, varargin{:}); end function varargout = lt(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1596, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1679, self, varargin{:}); end function self = BerdyDynamicVariable(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -45,14 +45,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1597, varargin{:}); + tmp = iDynTreeMEX(1680, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1598, self); + iDynTreeMEX(1681, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariables.m b/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariables.m index 4b5412eafc..2135593e57 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariables.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdyDynamicVariables.m @@ -4,49 +4,49 @@ this = iDynTreeMEX(3, self); end function varargout = pop(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(96, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(171, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(97, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(172, self, varargin{:}); end function varargout = setbrace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(98, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(173, self, varargin{:}); end function varargout = append(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(99, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(174, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(100, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(175, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(101, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(176, self, varargin{:}); end function varargout = swap(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(102, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(177, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(103, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(178, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(104, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(179, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(105, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(180, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(106, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(181, self, varargin{:}); end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(107, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(182, self, varargin{:}); end function varargout = get_allocator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(108, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(183, self, varargin{:}); end function varargout = pop_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(109, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(184, self, varargin{:}); end function varargout = erase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(110, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(185, self, varargin{:}); end function self = BerdyDynamicVariables(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -54,38 +54,38 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(111, varargin{:}); + tmp = iDynTreeMEX(186, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = push_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(112, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(187, self, varargin{:}); end function varargout = front(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(113, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(188, self, varargin{:}); end function varargout = back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(114, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(189, self, varargin{:}); end function varargout = assign(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(115, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(190, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(116, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(191, self, varargin{:}); end function varargout = insert(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(117, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(192, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(118, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(193, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(119, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(194, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(120, self); + iDynTreeMEX(195, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdyHelper.m b/bindings/matlab/autogenerated/+iDynTree/BerdyHelper.m index 7383ec1ce4..51229eea16 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdyHelper.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdyHelper.m @@ -9,107 +9,107 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1599, varargin{:}); + tmp = iDynTreeMEX(1682, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = dynamicTraversal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1600, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1683, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1601, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1684, self, varargin{:}); end function varargout = sensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1602, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1685, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1603, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1686, self, varargin{:}); end function varargout = init(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1604, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1687, self, varargin{:}); end function varargout = getOptions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1605, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1688, self, varargin{:}); end function varargout = getNrOfDynamicVariables(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1606, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1689, self, varargin{:}); end function varargout = getNrOfDynamicEquations(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1607, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1690, self, varargin{:}); end function varargout = getNrOfSensorsMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1608, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1691, self, varargin{:}); end function varargout = resizeAndZeroBerdyMatrices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1609, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1692, self, varargin{:}); end function varargout = getBerdyMatrices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1610, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1693, self, varargin{:}); end function varargout = getSensorsOrdering(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1611, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1694, self, varargin{:}); end function varargout = getRangeSensorVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1612, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1695, self, varargin{:}); end function varargout = getRangeDOFSensorVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1613, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1696, self, varargin{:}); end function varargout = getRangeJointSensorVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1614, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1697, self, varargin{:}); end function varargout = getRangeLinkSensorVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1615, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1698, self, varargin{:}); end function varargout = getRangeRCMSensorVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1616, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1699, self, varargin{:}); end function varargout = getRangeLinkVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1617, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1700, self, varargin{:}); end function varargout = getRangeJointVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1618, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1701, self, varargin{:}); end function varargout = getRangeDOFVariable(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1619, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1702, self, varargin{:}); end function varargout = getDynamicVariablesOrdering(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1620, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1703, self, varargin{:}); end function varargout = serializeDynamicVariables(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1621, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1704, self, varargin{:}); end function varargout = serializeSensorVariables(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1622, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1705, self, varargin{:}); end function varargout = serializeDynamicVariablesComputedFromFixedBaseRNEA(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1623, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1706, self, varargin{:}); end function varargout = extractJointTorquesFromDynamicVariables(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1624, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1707, self, varargin{:}); end function varargout = extractLinkNetExternalWrenchesFromDynamicVariables(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1625, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1708, self, varargin{:}); end function varargout = updateKinematicsFromFloatingBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1626, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1709, self, varargin{:}); end function varargout = updateKinematicsFromFixedBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1627, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1710, self, varargin{:}); end function varargout = updateKinematicsFromTraversalFixedBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1628, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1711, self, varargin{:}); end function varargout = setNetExternalWrenchMeasurementFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1629, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1712, self, varargin{:}); end function varargout = getNetExternalWrenchMeasurementFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1630, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1713, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1631, self); + iDynTreeMEX(1714, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdyOptions.m b/bindings/matlab/autogenerated/+iDynTree/BerdyOptions.m index 48a7e84c61..75fe6ff6e5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdyOptions.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdyOptions.m @@ -9,7 +9,7 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1560, varargin{:}); + tmp = iDynTreeMEX(1643, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end @@ -18,88 +18,88 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1561, self); + varargout{1} = iDynTreeMEX(1644, self); else nargoutchk(0, 0) - iDynTreeMEX(1562, self, varargin{1}); + iDynTreeMEX(1645, self, varargin{1}); end end function varargout = includeAllNetExternalWrenchesAsDynamicVariables(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1563, self); + varargout{1} = iDynTreeMEX(1646, self); else nargoutchk(0, 0) - iDynTreeMEX(1564, self, varargin{1}); + iDynTreeMEX(1647, self, varargin{1}); end end function varargout = includeAllJointAccelerationsAsSensors(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1565, self); + varargout{1} = iDynTreeMEX(1648, self); else nargoutchk(0, 0) - iDynTreeMEX(1566, self, varargin{1}); + iDynTreeMEX(1649, self, varargin{1}); end end function varargout = includeAllJointTorquesAsSensors(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1567, self); + varargout{1} = iDynTreeMEX(1650, self); else nargoutchk(0, 0) - iDynTreeMEX(1568, self, varargin{1}); + iDynTreeMEX(1651, self, varargin{1}); end end function varargout = includeAllNetExternalWrenchesAsSensors(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1569, self); + varargout{1} = iDynTreeMEX(1652, self); else nargoutchk(0, 0) - iDynTreeMEX(1570, self, varargin{1}); + iDynTreeMEX(1653, self, varargin{1}); end end function varargout = includeFixedBaseExternalWrench(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1571, self); + varargout{1} = iDynTreeMEX(1654, self); else nargoutchk(0, 0) - iDynTreeMEX(1572, self, varargin{1}); + iDynTreeMEX(1655, self, varargin{1}); end end function varargout = jointOnWhichTheInternalWrenchIsMeasured(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1573, self); + varargout{1} = iDynTreeMEX(1656, self); else nargoutchk(0, 0) - iDynTreeMEX(1574, self, varargin{1}); + iDynTreeMEX(1657, self, varargin{1}); end end function varargout = baseLink(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1575, self); + varargout{1} = iDynTreeMEX(1658, self); else nargoutchk(0, 0) - iDynTreeMEX(1576, self, varargin{1}); + iDynTreeMEX(1659, self, varargin{1}); end end function varargout = checkConsistency(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1577, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1660, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1578, self); + iDynTreeMEX(1661, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdySensor.m b/bindings/matlab/autogenerated/+iDynTree/BerdySensor.m index cd55bfd083..1f4c4da34d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdySensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdySensor.m @@ -7,37 +7,37 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1579, self); + varargout{1} = iDynTreeMEX(1662, self); else nargoutchk(0, 0) - iDynTreeMEX(1580, self, varargin{1}); + iDynTreeMEX(1663, self, varargin{1}); end end function varargout = id(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1581, self); + varargout{1} = iDynTreeMEX(1664, self); else nargoutchk(0, 0) - iDynTreeMEX(1582, self, varargin{1}); + iDynTreeMEX(1665, self, varargin{1}); end end function varargout = range(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1583, self); + varargout{1} = iDynTreeMEX(1666, self); else nargoutchk(0, 0) - iDynTreeMEX(1584, self, varargin{1}); + iDynTreeMEX(1667, self, varargin{1}); end end function varargout = eq(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1585, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1668, self, varargin{:}); end function varargout = lt(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1586, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1669, self, varargin{:}); end function self = BerdySensor(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -45,14 +45,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1587, varargin{:}); + tmp = iDynTreeMEX(1670, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1588, self); + iDynTreeMEX(1671, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdySensors.m b/bindings/matlab/autogenerated/+iDynTree/BerdySensors.m index 25109e1c44..8f329c7f01 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdySensors.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdySensors.m @@ -4,49 +4,49 @@ this = iDynTreeMEX(3, self); end function varargout = pop(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(71, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(146, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(72, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(147, self, varargin{:}); end function varargout = setbrace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(73, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(148, self, varargin{:}); end function varargout = append(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(74, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(149, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(75, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(150, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(76, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(151, self, varargin{:}); end function varargout = swap(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(77, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(152, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(78, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(153, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(79, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(154, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(80, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(155, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(81, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(156, self, varargin{:}); end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(82, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(157, self, varargin{:}); end function varargout = get_allocator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(83, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(158, self, varargin{:}); end function varargout = pop_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(84, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(159, self, varargin{:}); end function varargout = erase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(85, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(160, self, varargin{:}); end function self = BerdySensors(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -54,38 +54,38 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(86, varargin{:}); + tmp = iDynTreeMEX(161, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = push_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(87, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(162, self, varargin{:}); end function varargout = front(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(88, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(163, self, varargin{:}); end function varargout = back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(89, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(164, self, varargin{:}); end function varargout = assign(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(90, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(165, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(91, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(166, self, varargin{:}); end function varargout = insert(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(92, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(167, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(93, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(168, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(94, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(169, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(95, self); + iDynTreeMEX(170, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/BerdySparseMAPSolver.m b/bindings/matlab/autogenerated/+iDynTree/BerdySparseMAPSolver.m index 4ff118081d..aba2bdc020 100644 --- a/bindings/matlab/autogenerated/+iDynTree/BerdySparseMAPSolver.m +++ b/bindings/matlab/autogenerated/+iDynTree/BerdySparseMAPSolver.m @@ -9,58 +9,58 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1632, varargin{:}); + tmp = iDynTreeMEX(1715, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1633, self); + iDynTreeMEX(1716, self); self.SwigClear(); end end function varargout = setDynamicsConstraintsPriorCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1634, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1717, self, varargin{:}); end function varargout = setDynamicsRegularizationPriorCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1635, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1718, self, varargin{:}); end function varargout = setDynamicsRegularizationPriorExpectedValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1636, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1719, self, varargin{:}); end function varargout = setMeasurementsPriorCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1637, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1720, self, varargin{:}); end function varargout = dynamicsConstraintsPriorCovarianceInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1638, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1721, self, varargin{:}); end function varargout = dynamicsRegularizationPriorCovarianceInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1639, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1722, self, varargin{:}); end function varargout = dynamicsRegularizationPriorExpectedValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1640, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1723, self, varargin{:}); end function varargout = measurementsPriorCovarianceInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1641, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1724, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1642, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1725, self, varargin{:}); end function varargout = initialize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1643, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1726, self, varargin{:}); end function varargout = updateEstimateInformationFixedBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1644, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1727, self, varargin{:}); end function varargout = updateEstimateInformationFloatingBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1645, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1728, self, varargin{:}); end function varargout = doEstimate(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1646, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1729, self, varargin{:}); end function varargout = getLastEstimate(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1647, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1730, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/Box.m b/bindings/matlab/autogenerated/+iDynTree/Box.m index 66105f38b9..e65c8e674e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Box.m +++ b/bindings/matlab/autogenerated/+iDynTree/Box.m @@ -2,30 +2,30 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1011, self); + iDynTreeMEX(1084, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1012, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1085, self, varargin{:}); end function varargout = getX(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1013, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1086, self, varargin{:}); end function varargout = setX(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1014, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1087, self, varargin{:}); end function varargout = getY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1015, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1088, self, varargin{:}); end function varargout = setY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1016, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1089, self, varargin{:}); end function varargout = getZ(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1017, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1090, self, varargin{:}); end function varargout = setZ(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1018, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1091, self, varargin{:}); end function self = Box(varargin) self@iDynTree.SolidShape(iDynTreeSwigRef.Null); @@ -34,7 +34,7 @@ function delete(self) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1019, varargin{:}); + tmp = iDynTreeMEX(1092, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ClassicalAcc.m b/bindings/matlab/autogenerated/+iDynTree/ClassicalAcc.m index 0fa585411c..2b90350431 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ClassicalAcc.m +++ b/bindings/matlab/autogenerated/+iDynTree/ClassicalAcc.m @@ -7,30 +7,30 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(522, varargin{:}); + tmp = iDynTreeMEX(588, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = changeCoordFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(523, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(589, self, varargin{:}); end function varargout = fromSpatial(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(525, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(591, self, varargin{:}); end function varargout = toSpatial(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(526, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(592, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(527, self); + iDynTreeMEX(593, self); self.SwigClear(); end end end methods(Static) function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(524, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(590, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ColorViz.m b/bindings/matlab/autogenerated/+iDynTree/ColorViz.m index da6c9d2550..563373f1fe 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ColorViz.m +++ b/bindings/matlab/autogenerated/+iDynTree/ColorViz.m @@ -7,40 +7,40 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1866, self); + varargout{1} = iDynTreeMEX(1949, self); else nargoutchk(0, 0) - iDynTreeMEX(1867, self, varargin{1}); + iDynTreeMEX(1950, self, varargin{1}); end end function varargout = g(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1868, self); + varargout{1} = iDynTreeMEX(1951, self); else nargoutchk(0, 0) - iDynTreeMEX(1869, self, varargin{1}); + iDynTreeMEX(1952, self, varargin{1}); end end function varargout = b(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1870, self); + varargout{1} = iDynTreeMEX(1953, self); else nargoutchk(0, 0) - iDynTreeMEX(1871, self, varargin{1}); + iDynTreeMEX(1954, self, varargin{1}); end end function varargout = a(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1872, self); + varargout{1} = iDynTreeMEX(1955, self); else nargoutchk(0, 0) - iDynTreeMEX(1873, self, varargin{1}); + iDynTreeMEX(1956, self, varargin{1}); end end function self = ColorViz(varargin) @@ -49,14 +49,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1874, varargin{:}); + tmp = iDynTreeMEX(1957, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1875, self); + iDynTreeMEX(1958, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/CompositeRigidBodyAlgorithm.m b/bindings/matlab/autogenerated/+iDynTree/CompositeRigidBodyAlgorithm.m index 716c0bc34a..c7d1cc0233 100644 --- a/bindings/matlab/autogenerated/+iDynTree/CompositeRigidBodyAlgorithm.m +++ b/bindings/matlab/autogenerated/+iDynTree/CompositeRigidBodyAlgorithm.m @@ -1,3 +1,3 @@ function varargout = CompositeRigidBodyAlgorithm(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1239, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1464, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentum.m b/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentum.m index 97f3de2f4c..7a5c174c03 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentum.m +++ b/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentum.m @@ -1,3 +1,3 @@ function varargout = ComputeLinearAndAngularMomentum(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1236, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1461, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentumDerivativeBias.m b/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentumDerivativeBias.m index 037c2b8d48..13a68f6419 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentumDerivativeBias.m +++ b/bindings/matlab/autogenerated/+iDynTree/ComputeLinearAndAngularMomentumDerivativeBias.m @@ -1,3 +1,3 @@ function varargout = ComputeLinearAndAngularMomentumDerivativeBias(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1237, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1462, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ContactWrench.m b/bindings/matlab/autogenerated/+iDynTree/ContactWrench.m index bddf492578..b858c218ed 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ContactWrench.m +++ b/bindings/matlab/autogenerated/+iDynTree/ContactWrench.m @@ -4,13 +4,13 @@ this = iDynTreeMEX(3, self); end function varargout = contactId(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1141, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1272, self, varargin{:}); end function varargout = contactPoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1142, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1273, self, varargin{:}); end function varargout = contactWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1143, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1274, self, varargin{:}); end function self = ContactWrench(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -18,14 +18,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1144, varargin{:}); + tmp = iDynTreeMEX(1275, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1145, self); + iDynTreeMEX(1276, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ConvexHullProjectionConstraint.m b/bindings/matlab/autogenerated/+iDynTree/ConvexHullProjectionConstraint.m index 6eabceb49a..a19df5d343 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ConvexHullProjectionConstraint.m +++ b/bindings/matlab/autogenerated/+iDynTree/ConvexHullProjectionConstraint.m @@ -4,118 +4,118 @@ this = iDynTreeMEX(3, self); end function varargout = setActive(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2024, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2107, self, varargin{:}); end function varargout = isActive(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2025, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2108, self, varargin{:}); end function varargout = getNrOfConstraints(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2026, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2109, self, varargin{:}); end function varargout = projectedConvexHull(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2027, self); + varargout{1} = iDynTreeMEX(2110, self); else nargoutchk(0, 0) - iDynTreeMEX(2028, self, varargin{1}); + iDynTreeMEX(2111, self, varargin{1}); end end function varargout = A(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2029, self); + varargout{1} = iDynTreeMEX(2112, self); else nargoutchk(0, 0) - iDynTreeMEX(2030, self, varargin{1}); + iDynTreeMEX(2113, self, varargin{1}); end end function varargout = b(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2031, self); + varargout{1} = iDynTreeMEX(2114, self); else nargoutchk(0, 0) - iDynTreeMEX(2032, self, varargin{1}); + iDynTreeMEX(2115, self, varargin{1}); end end function varargout = P(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2033, self); + varargout{1} = iDynTreeMEX(2116, self); else nargoutchk(0, 0) - iDynTreeMEX(2034, self, varargin{1}); + iDynTreeMEX(2117, self, varargin{1}); end end function varargout = Pdirection(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2035, self); + varargout{1} = iDynTreeMEX(2118, self); else nargoutchk(0, 0) - iDynTreeMEX(2036, self, varargin{1}); + iDynTreeMEX(2119, self, varargin{1}); end end function varargout = AtimesP(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2037, self); + varargout{1} = iDynTreeMEX(2120, self); else nargoutchk(0, 0) - iDynTreeMEX(2038, self, varargin{1}); + iDynTreeMEX(2121, self, varargin{1}); end end function varargout = o(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2039, self); + varargout{1} = iDynTreeMEX(2122, self); else nargoutchk(0, 0) - iDynTreeMEX(2040, self, varargin{1}); + iDynTreeMEX(2123, self, varargin{1}); end end function varargout = buildConvexHull(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2041, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2124, self, varargin{:}); end function varargout = supportFrameIndices(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2042, self); + varargout{1} = iDynTreeMEX(2125, self); else nargoutchk(0, 0) - iDynTreeMEX(2043, self, varargin{1}); + iDynTreeMEX(2126, self, varargin{1}); end end function varargout = absoluteFrame_X_supportFrame(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2044, self); + varargout{1} = iDynTreeMEX(2127, self); else nargoutchk(0, 0) - iDynTreeMEX(2045, self, varargin{1}); + iDynTreeMEX(2128, self, varargin{1}); end end function varargout = project(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2046, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2129, self, varargin{:}); end function varargout = computeMargin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2047, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2130, self, varargin{:}); end function varargout = setProjectionAlongDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2048, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2131, self, varargin{:}); end function varargout = projectAlongDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2049, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2132, self, varargin{:}); end function self = ConvexHullProjectionConstraint(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -123,14 +123,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(2050, varargin{:}); + tmp = iDynTreeMEX(2133, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(2051, self); + iDynTreeMEX(2134, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/CreateModelFromDHChain.m b/bindings/matlab/autogenerated/+iDynTree/CreateModelFromDHChain.m index 60ff421775..3290daedc1 100644 --- a/bindings/matlab/autogenerated/+iDynTree/CreateModelFromDHChain.m +++ b/bindings/matlab/autogenerated/+iDynTree/CreateModelFromDHChain.m @@ -1,3 +1,3 @@ function varargout = CreateModelFromDHChain(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1294, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1519, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/Cylinder.m b/bindings/matlab/autogenerated/+iDynTree/Cylinder.m index add10b5855..d550355e7e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Cylinder.m +++ b/bindings/matlab/autogenerated/+iDynTree/Cylinder.m @@ -2,24 +2,24 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1020, self); + iDynTreeMEX(1093, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1021, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1094, self, varargin{:}); end function varargout = getLength(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1022, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1095, self, varargin{:}); end function varargout = setLength(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1023, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1096, self, varargin{:}); end function varargout = getRadius(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1024, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1097, self, varargin{:}); end function varargout = setRadius(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1025, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1098, self, varargin{:}); end function self = Cylinder(varargin) self@iDynTree.SolidShape(iDynTreeSwigRef.Null); @@ -28,7 +28,7 @@ function delete(self) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1026, varargin{:}); + tmp = iDynTreeMEX(1099, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end diff --git a/bindings/matlab/autogenerated/+iDynTree/DHChain.m b/bindings/matlab/autogenerated/+iDynTree/DHChain.m index 53d5732c2d..bcbff584d6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DHChain.m +++ b/bindings/matlab/autogenerated/+iDynTree/DHChain.m @@ -4,37 +4,37 @@ this = iDynTreeMEX(3, self); end function varargout = setNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1278, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1503, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1279, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1504, self, varargin{:}); end function varargout = setH0(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1280, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1505, self, varargin{:}); end function varargout = getH0(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1281, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1506, self, varargin{:}); end function varargout = setHN(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1282, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1507, self, varargin{:}); end function varargout = getHN(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1283, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1508, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1284, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1509, self, varargin{:}); end function varargout = getDOFName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1285, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1510, self, varargin{:}); end function varargout = setDOFName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1286, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1511, self, varargin{:}); end function varargout = toModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1287, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1512, self, varargin{:}); end function varargout = fromModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1288, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1513, self, varargin{:}); end function self = DHChain(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -42,14 +42,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1289, varargin{:}); + tmp = iDynTreeMEX(1514, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1290, self); + iDynTreeMEX(1515, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DHLink.m b/bindings/matlab/autogenerated/+iDynTree/DHLink.m index a85f85ec32..50fe0fb306 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DHLink.m +++ b/bindings/matlab/autogenerated/+iDynTree/DHLink.m @@ -7,60 +7,60 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1264, self); + varargout{1} = iDynTreeMEX(1489, self); else nargoutchk(0, 0) - iDynTreeMEX(1265, self, varargin{1}); + iDynTreeMEX(1490, self, varargin{1}); end end function varargout = D(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1266, self); + varargout{1} = iDynTreeMEX(1491, self); else nargoutchk(0, 0) - iDynTreeMEX(1267, self, varargin{1}); + iDynTreeMEX(1492, self, varargin{1}); end end function varargout = Alpha(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1268, self); + varargout{1} = iDynTreeMEX(1493, self); else nargoutchk(0, 0) - iDynTreeMEX(1269, self, varargin{1}); + iDynTreeMEX(1494, self, varargin{1}); end end function varargout = Offset(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1270, self); + varargout{1} = iDynTreeMEX(1495, self); else nargoutchk(0, 0) - iDynTreeMEX(1271, self, varargin{1}); + iDynTreeMEX(1496, self, varargin{1}); end end function varargout = Min(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1272, self); + varargout{1} = iDynTreeMEX(1497, self); else nargoutchk(0, 0) - iDynTreeMEX(1273, self, varargin{1}); + iDynTreeMEX(1498, self, varargin{1}); end end function varargout = Max(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1274, self); + varargout{1} = iDynTreeMEX(1499, self); else nargoutchk(0, 0) - iDynTreeMEX(1275, self, varargin{1}); + iDynTreeMEX(1500, self, varargin{1}); end end function self = DHLink(varargin) @@ -69,14 +69,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1276, varargin{:}); + tmp = iDynTreeMEX(1501, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1277, self); + iDynTreeMEX(1502, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DIRECTIONAL_LIGHT.m b/bindings/matlab/autogenerated/+iDynTree/DIRECTIONAL_LIGHT.m index d64a88e19f..54232142c3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DIRECTIONAL_LIGHT.m +++ b/bindings/matlab/autogenerated/+iDynTree/DIRECTIONAL_LIGHT.m @@ -1,7 +1,7 @@ function v = DIRECTIONAL_LIGHT() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 35); + vInitialized = iDynTreeMEX(0, 37); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOFSpatialForceArray.m b/bindings/matlab/autogenerated/+iDynTree/DOFSpatialForceArray.m index 57dbfef46c..2c5ccb322d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOFSpatialForceArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOFSpatialForceArray.m @@ -9,23 +9,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1096, varargin{:}); + tmp = iDynTreeMEX(1227, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1097, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1228, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1098, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1229, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1099, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1230, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1100, self); + iDynTreeMEX(1231, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOFSpatialMotionArray.m b/bindings/matlab/autogenerated/+iDynTree/DOFSpatialMotionArray.m index 7e49ad6dc9..3a5b811cd0 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOFSpatialMotionArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOFSpatialMotionArray.m @@ -9,23 +9,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1101, varargin{:}); + tmp = iDynTreeMEX(1232, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1102, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1233, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1103, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1234, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1104, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1235, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1105, self); + iDynTreeMEX(1236, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION.m b/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION.m index 7e932b0e92..ce646c72e7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION.m @@ -1,7 +1,7 @@ function v = DOF_ACCELERATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 22); + vInitialized = iDynTreeMEX(0, 24); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION_SENSOR.m index 9e54ee2bbc..9b535b1651 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_ACCELERATION_SENSOR.m @@ -1,7 +1,7 @@ function v = DOF_ACCELERATION_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 29); + vInitialized = iDynTreeMEX(0, 31); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_INDEX.m b/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_INDEX.m index 9127f18cd3..349e04297b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_INDEX.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_INDEX.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(735); + varargout{1} = iDynTreeMEX(784); else nargoutchk(0,0) - iDynTreeMEX(736,varargin{1}); + iDynTreeMEX(785,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_NAME.m b/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_NAME.m index 61586120d4..c882f608d4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_NAME.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_INVALID_NAME.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(737); + varargout{1} = iDynTreeMEX(786); else nargoutchk(0,0) - iDynTreeMEX(738,varargin{1}); + iDynTreeMEX(787,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE.m b/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE.m index 1bb4d0b1c6..ed528b0562 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE.m @@ -1,7 +1,7 @@ function v = DOF_TORQUE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 20); + vInitialized = iDynTreeMEX(0, 22); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE_SENSOR.m index 7418cea775..b7a2646e17 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/DOF_TORQUE_SENSOR.m @@ -1,7 +1,7 @@ function v = DOF_TORQUE_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 30); + vInitialized = iDynTreeMEX(0, 32); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/Direction.m b/bindings/matlab/autogenerated/+iDynTree/Direction.m index 107e95ac6b..da57c73669 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Direction.m +++ b/bindings/matlab/autogenerated/+iDynTree/Direction.m @@ -7,39 +7,39 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(528, varargin{:}); + tmp = iDynTreeMEX(594, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = Normalize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(529, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(595, self, varargin{:}); end function varargout = isParallel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(530, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(596, self, varargin{:}); end function varargout = isPerpendicular(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(531, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(597, self, varargin{:}); end function varargout = reverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(532, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(598, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(533, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(599, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(534, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(600, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(536, self); + iDynTreeMEX(602, self); self.SwigClear(); end end end methods(Static) function varargout = Default(varargin) - [varargout{1:nargout}] = iDynTreeMEX(535, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(601, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DiscreteExtendedKalmanFilterHelper.m b/bindings/matlab/autogenerated/+iDynTree/DiscreteExtendedKalmanFilterHelper.m index 8bb6445131..6388fecff3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DiscreteExtendedKalmanFilterHelper.m +++ b/bindings/matlab/autogenerated/+iDynTree/DiscreteExtendedKalmanFilterHelper.m @@ -4,65 +4,65 @@ this = iDynTreeMEX(3, self); end function varargout = ekf_f(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1699, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1782, self, varargin{:}); end function varargout = ekf_h(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1700, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1783, self, varargin{:}); end function varargout = ekfComputeJacobianF(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1701, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1784, self, varargin{:}); end function varargout = ekfComputeJacobianH(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1702, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1785, self, varargin{:}); end function varargout = ekfPredict(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1703, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1786, self, varargin{:}); end function varargout = ekfUpdate(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1704, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1787, self, varargin{:}); end function varargout = ekfInit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1705, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1788, self, varargin{:}); end function varargout = ekfReset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1706, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1789, self, varargin{:}); end function varargout = ekfSetMeasurementVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1707, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1790, self, varargin{:}); end function varargout = ekfSetInputVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1708, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1791, self, varargin{:}); end function varargout = ekfSetInitialState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1709, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1792, self, varargin{:}); end function varargout = ekfSetStateCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1710, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1793, self, varargin{:}); end function varargout = ekfSetSystemNoiseCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1711, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1794, self, varargin{:}); end function varargout = ekfSetMeasurementNoiseCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1712, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1795, self, varargin{:}); end function varargout = ekfSetStateSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1713, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1796, self, varargin{:}); end function varargout = ekfSetInputSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1714, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1797, self, varargin{:}); end function varargout = ekfSetOutputSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1715, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1798, self, varargin{:}); end function varargout = ekfGetStates(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1716, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1799, self, varargin{:}); end function varargout = ekfGetStateCovariance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1717, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1800, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1718, self); + iDynTreeMEX(1801, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Dummy.m b/bindings/matlab/autogenerated/+iDynTree/Dummy.m index 2d2c0bd625..0f0cb312f7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Dummy.m +++ b/bindings/matlab/autogenerated/+iDynTree/Dummy.m @@ -9,14 +9,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(489, varargin{:}); + tmp = iDynTreeMEX(555, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(490, self); + iDynTreeMEX(556, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DynamicMatrixView.m b/bindings/matlab/autogenerated/+iDynTree/DynamicMatrixView.m index 3cde594d88..e5b07d4839 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DynamicMatrixView.m +++ b/bindings/matlab/autogenerated/+iDynTree/DynamicMatrixView.m @@ -9,29 +9,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(720, varargin{:}); + tmp = iDynTreeMEX(769, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = storageOrder(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(721, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(770, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(722, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(771, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(723, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(772, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(724, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(773, self, varargin{:}); end function varargout = block(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(725, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(774, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(726, self); + iDynTreeMEX(775, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/DynamicSpan.m b/bindings/matlab/autogenerated/+iDynTree/DynamicSpan.m index 5681600cad..adff3e9cce 100644 --- a/bindings/matlab/autogenerated/+iDynTree/DynamicSpan.m +++ b/bindings/matlab/autogenerated/+iDynTree/DynamicSpan.m @@ -9,78 +9,78 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(699, varargin{:}); + tmp = iDynTreeMEX(748, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(700, self); + iDynTreeMEX(749, self); self.SwigClear(); end end function varargout = first(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(701, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(750, self, varargin{:}); end function varargout = last(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(702, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(751, self, varargin{:}); end function varargout = subspan(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(703, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(752, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(704, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(753, self, varargin{:}); end function varargout = size_bytes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(705, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(754, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(706, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(755, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(707, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(756, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(708, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(757, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(709, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(758, self, varargin{:}); end function varargout = at(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(710, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(759, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(711, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(760, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(712, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(761, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(713, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(762, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(714, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(763, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(715, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(764, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(716, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(765, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(717, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(766, self, varargin{:}); end function varargout = crbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(718, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(767, self, varargin{:}); end function varargout = crend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(719, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(768, self, varargin{:}); end end methods(Static) function v = extent() - v = iDynTreeMEX(698); + v = iDynTreeMEX(747); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ExtWrenchesAndJointTorquesEstimator.m b/bindings/matlab/autogenerated/+iDynTree/ExtWrenchesAndJointTorquesEstimator.m index f04c31e1d4..7254d6c1fe 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ExtWrenchesAndJointTorquesEstimator.m +++ b/bindings/matlab/autogenerated/+iDynTree/ExtWrenchesAndJointTorquesEstimator.m @@ -9,52 +9,58 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1533, varargin{:}); + tmp = iDynTreeMEX(1614, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1534, self); + iDynTreeMEX(1615, self); self.SwigClear(); end end + function varargout = setModel(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1616, self, varargin{:}); + end function varargout = setModelAndSensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1535, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1617, self, varargin{:}); end function varargout = loadModelAndSensorsFromFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1536, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1618, self, varargin{:}); end function varargout = loadModelAndSensorsFromFileWithSpecifiedDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1537, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1619, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1538, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1620, self, varargin{:}); end function varargout = sensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1539, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1621, self, varargin{:}); end function varargout = submodels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1540, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1622, self, varargin{:}); end function varargout = updateKinematicsFromFloatingBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1541, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1623, self, varargin{:}); end function varargout = updateKinematicsFromFixedBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1542, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1624, self, varargin{:}); end function varargout = computeExpectedFTSensorsMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1543, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1625, self, varargin{:}); + end + function varargout = computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1626, self, varargin{:}); end function varargout = estimateExtWrenchesAndJointTorques(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1544, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1627, self, varargin{:}); end function varargout = checkThatTheModelIsStill(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1545, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1628, self, varargin{:}); end function varargout = estimateLinkNetWrenchesWithoutGravity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1546, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1629, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ExternalMesh.m b/bindings/matlab/autogenerated/+iDynTree/ExternalMesh.m index 25ab62db30..5f9b6b6553 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ExternalMesh.m +++ b/bindings/matlab/autogenerated/+iDynTree/ExternalMesh.m @@ -2,27 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1027, self); + iDynTreeMEX(1100, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1028, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1101, self, varargin{:}); end function varargout = getFilename(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1029, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1102, self, varargin{:}); + end + function varargout = getPackageDirs(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1103, self, varargin{:}); end function varargout = getFileLocationOnLocalFileSystem(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1030, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1104, self, varargin{:}); end function varargout = setFilename(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1031, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1105, self, varargin{:}); + end + function varargout = setPackageDirs(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1106, self, varargin{:}); end function varargout = getScale(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1032, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1107, self, varargin{:}); end function varargout = setScale(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1033, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1108, self, varargin{:}); end function self = ExternalMesh(varargin) self@iDynTree.SolidShape(iDynTreeSwigRef.Null); @@ -31,7 +37,7 @@ function delete(self) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1034, varargin{:}); + tmp = iDynTreeMEX(1109, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ExtractDHChainFromModel.m b/bindings/matlab/autogenerated/+iDynTree/ExtractDHChainFromModel.m index 75dadb6435..245183b42d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ExtractDHChainFromModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/ExtractDHChainFromModel.m @@ -1,3 +1,3 @@ function varargout = ExtractDHChainFromModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1293, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1518, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_INDEX.m b/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_INDEX.m index ee3cd9fece..5a06a2b4d5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_INDEX.m +++ b/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_INDEX.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(739); + varargout{1} = iDynTreeMEX(788); else nargoutchk(0,0) - iDynTreeMEX(740,varargin{1}); + iDynTreeMEX(789,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_NAME.m b/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_NAME.m index 6bb3d75c42..2fd3262035 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_NAME.m +++ b/bindings/matlab/autogenerated/+iDynTree/FRAME_INVALID_NAME.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(741); + varargout{1} = iDynTreeMEX(790); else nargoutchk(0,0) - iDynTreeMEX(742,varargin{1}); + iDynTreeMEX(791,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FULL_WRENCH.m b/bindings/matlab/autogenerated/+iDynTree/FULL_WRENCH.m index 1f3e6ff6b5..8ab00c1343 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FULL_WRENCH.m +++ b/bindings/matlab/autogenerated/+iDynTree/FULL_WRENCH.m @@ -1,7 +1,7 @@ function v = FULL_WRENCH() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 10); + vInitialized = iDynTreeMEX(0, 12); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/FixedJoint.m b/bindings/matlab/autogenerated/+iDynTree/FixedJoint.m index 8e1f53bfa6..33af42b27c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FixedJoint.m +++ b/bindings/matlab/autogenerated/+iDynTree/FixedJoint.m @@ -7,103 +7,121 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(827, varargin{:}); + tmp = iDynTreeMEX(882, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(828, self); + iDynTreeMEX(883, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(829, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(884, self, varargin{:}); end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(830, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(885, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(831, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(886, self, varargin{:}); end function varargout = setAttachedLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(832, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(887, self, varargin{:}); end function varargout = setRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(833, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(888, self, varargin{:}); end function varargout = getFirstAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(834, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(889, self, varargin{:}); end function varargout = getSecondAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(835, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(890, self, varargin{:}); end function varargout = getRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(836, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(891, self, varargin{:}); end function varargout = getTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(837, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(892, self, varargin{:}); end function varargout = getTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(838, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(893, self, varargin{:}); end function varargout = getMotionSubspaceVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(839, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(894, self, varargin{:}); end function varargout = computeChildPosVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(840, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(895, self, varargin{:}); end function varargout = computeChildVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(841, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(896, self, varargin{:}); end function varargout = computeChildVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(842, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(897, self, varargin{:}); end function varargout = computeChildAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(843, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(898, self, varargin{:}); end function varargout = computeChildBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(844, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(899, self, varargin{:}); end function varargout = computeJointTorque(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(845, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(900, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(846, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(901, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(847, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(902, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(848, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(903, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(849, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(904, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(850, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(905, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(851, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(906, self, varargin{:}); end function varargout = hasPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(852, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(907, self, varargin{:}); end function varargout = enablePosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(853, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(908, self, varargin{:}); end function varargout = getPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(854, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(909, self, varargin{:}); end function varargout = getMinPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(855, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(910, self, varargin{:}); end function varargout = getMaxPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(856, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(911, self, varargin{:}); end function varargout = setPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(857, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(912, self, varargin{:}); + end + function varargout = getJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(913, self, varargin{:}); + end + function varargout = setJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(914, self, varargin{:}); + end + function varargout = getDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(915, self, varargin{:}); + end + function varargout = getStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(916, self, varargin{:}); + end + function varargout = setDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(917, self, varargin{:}); + end + function varargout = setStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(918, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardAccKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardAccKinematics.m index 0882e9c809..cd7c10aeab 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardAccKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardAccKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardAccKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1234, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1459, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardBiasAccKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardBiasAccKinematics.m index 567c6ef680..ed110d77a7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardBiasAccKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardBiasAccKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardBiasAccKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1235, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1460, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelAccKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelAccKinematics.m index 549945fba0..477ab021f9 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelAccKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelAccKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardPosVelAccKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1232, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1457, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelKinematics.m index 3434b59997..c5fe522e1a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardPosVelKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardPosVelKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1233, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1458, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardPositionKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardPositionKinematics.m index 3f3a7b072e..4a45772d68 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardPositionKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardPositionKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardPositionKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1230, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1455, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/ForwardVelAccKinematics.m b/bindings/matlab/autogenerated/+iDynTree/ForwardVelAccKinematics.m index 22a2fb73ad..763fb294e2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ForwardVelAccKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/ForwardVelAccKinematics.m @@ -1,3 +1,3 @@ function varargout = ForwardVelAccKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1231, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1456, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/FrameFreeFloatingJacobian.m b/bindings/matlab/autogenerated/+iDynTree/FrameFreeFloatingJacobian.m index 1bfdd10015..0818c28df0 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FrameFreeFloatingJacobian.m +++ b/bindings/matlab/autogenerated/+iDynTree/FrameFreeFloatingJacobian.m @@ -7,20 +7,20 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1106, varargin{:}); + tmp = iDynTreeMEX(1237, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1107, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1238, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1108, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1239, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1109, self); + iDynTreeMEX(1240, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingAcc.m b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingAcc.m index fc30ac6fd2..f758833f58 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingAcc.m +++ b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingAcc.m @@ -9,26 +9,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1135, varargin{:}); + tmp = iDynTreeMEX(1266, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1136, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1267, self, varargin{:}); end function varargout = baseAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1137, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1268, self, varargin{:}); end function varargout = jointAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1138, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1269, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1139, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1270, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1140, self); + iDynTreeMEX(1271, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingGeneralizedTorques.m b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingGeneralizedTorques.m index 966fabcaab..304e2e8c85 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingGeneralizedTorques.m +++ b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingGeneralizedTorques.m @@ -9,26 +9,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1123, varargin{:}); + tmp = iDynTreeMEX(1254, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1124, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1255, self, varargin{:}); end function varargout = baseWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1125, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1256, self, varargin{:}); end function varargout = jointTorques(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1126, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1257, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1127, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1258, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1128, self); + iDynTreeMEX(1259, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingMassMatrix.m b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingMassMatrix.m index 2222506043..14ba63720b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingMassMatrix.m +++ b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingMassMatrix.m @@ -7,17 +7,17 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1114, varargin{:}); + tmp = iDynTreeMEX(1245, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1115, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1246, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1116, self); + iDynTreeMEX(1247, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingPos.m b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingPos.m index f1495bc83f..67493716b3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingPos.m +++ b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingPos.m @@ -9,26 +9,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1117, varargin{:}); + tmp = iDynTreeMEX(1248, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1118, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1249, self, varargin{:}); end function varargout = worldBasePos(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1119, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1250, self, varargin{:}); end function varargout = jointPos(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1120, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1251, self, varargin{:}); end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1121, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1252, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1122, self); + iDynTreeMEX(1253, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingVel.m b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingVel.m index e6131f003e..aa0edf35d4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/FreeFloatingVel.m +++ b/bindings/matlab/autogenerated/+iDynTree/FreeFloatingVel.m @@ -9,26 +9,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1129, varargin{:}); + tmp = iDynTreeMEX(1260, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1130, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1261, self, varargin{:}); end function varargout = baseVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1131, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1262, self, varargin{:}); end function varargout = jointVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1132, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1263, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1133, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1264, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1134, self); + iDynTreeMEX(1265, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE.m b/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE.m index 7836113dac..41df58f227 100644 --- a/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE.m +++ b/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE.m @@ -1,7 +1,7 @@ function v = GYROSCOPE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 7); + vInitialized = iDynTreeMEX(0, 6); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE_SENSOR.m index 0568841180..0908c2edc1 100644 --- a/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/GYROSCOPE_SENSOR.m @@ -1,7 +1,7 @@ function v = GYROSCOPE_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 26); + vInitialized = iDynTreeMEX(0, 28); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/GeomVector3.m b/bindings/matlab/autogenerated/+iDynTree/GeomVector3.m index 55255b24b9..75cac96b39 100644 --- a/bindings/matlab/autogenerated/+iDynTree/GeomVector3.m +++ b/bindings/matlab/autogenerated/+iDynTree/GeomVector3.m @@ -7,41 +7,41 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(428, varargin{:}); + tmp = iDynTreeMEX(494, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = changeCoordFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(429, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(495, self, varargin{:}); end function varargout = compose(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(430, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(496, self, varargin{:}); end function varargout = inverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(431, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(497, self, varargin{:}); end function varargout = dot(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(432, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(498, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(433, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(499, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(434, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(500, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(435, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(501, self, varargin{:}); end function varargout = exp(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(436, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(502, self, varargin{:}); end function varargout = cross(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(437, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(503, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(438, self); + iDynTreeMEX(504, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/GyroscopeSensor.m b/bindings/matlab/autogenerated/+iDynTree/GyroscopeSensor.m index c1a1970c2b..df1d46a227 100644 --- a/bindings/matlab/autogenerated/+iDynTree/GyroscopeSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/GyroscopeSensor.m @@ -7,55 +7,55 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1391, varargin{:}); + tmp = iDynTreeMEX(1355, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1392, self); + iDynTreeMEX(1356, self); self.SwigClear(); end end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1393, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1357, self, varargin{:}); end function varargout = setLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1394, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1358, self, varargin{:}); end function varargout = setParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1395, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1359, self, varargin{:}); end function varargout = setParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1396, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1360, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1397, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1361, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1398, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1362, self, varargin{:}); end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1399, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1363, self, varargin{:}); end function varargout = getParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1400, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1364, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1401, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1365, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1402, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1366, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1403, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1367, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1404, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1368, self, varargin{:}); end function varargout = predictMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1405, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1369, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/IAttitudeEstimator.m b/bindings/matlab/autogenerated/+iDynTree/IAttitudeEstimator.m index 3cf3e1346a..e6cf754723 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IAttitudeEstimator.m +++ b/bindings/matlab/autogenerated/+iDynTree/IAttitudeEstimator.m @@ -5,39 +5,39 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1656, self); + iDynTreeMEX(1739, self); self.SwigClear(); end end function varargout = updateFilterWithMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1657, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1740, self, varargin{:}); end function varargout = propagateStates(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1658, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1741, self, varargin{:}); end function varargout = getOrientationEstimateAsRotationMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1659, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1742, self, varargin{:}); end function varargout = getOrientationEstimateAsQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1660, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1743, self, varargin{:}); end function varargout = getOrientationEstimateAsRPY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1661, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1744, self, varargin{:}); end function varargout = getInternalStateSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1662, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1745, self, varargin{:}); end function varargout = getInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1663, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1746, self, varargin{:}); end function varargout = getDefaultInternalInitialState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1664, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1747, self, varargin{:}); end function varargout = setInternalState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1665, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1748, self, varargin{:}); end function varargout = setInternalStateInitialOrientation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1666, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1749, self, varargin{:}); end function self = IAttitudeEstimator(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/ICamera.m b/bindings/matlab/autogenerated/+iDynTree/ICamera.m index 5bb99ff775..599476e1c1 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ICamera.m +++ b/bindings/matlab/autogenerated/+iDynTree/ICamera.m @@ -5,27 +5,27 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1859, self); + iDynTreeMEX(1942, self); self.SwigClear(); end end function varargout = setPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1860, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1943, self, varargin{:}); end function varargout = setTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1861, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1944, self, varargin{:}); end function varargout = getPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1862, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1945, self, varargin{:}); end function varargout = getTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1863, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1946, self, varargin{:}); end function varargout = setUpVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1864, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1947, self, varargin{:}); end function varargout = animator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1865, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1948, self, varargin{:}); end function self = ICamera(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/ICameraAnimator.m b/bindings/matlab/autogenerated/+iDynTree/ICameraAnimator.m index e9d9481a13..db48260e44 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ICameraAnimator.m +++ b/bindings/matlab/autogenerated/+iDynTree/ICameraAnimator.m @@ -4,29 +4,29 @@ this = iDynTreeMEX(3, self); end function varargout = enableMouseControl(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1851, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1934, self, varargin{:}); end function varargout = getMoveSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1852, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1935, self, varargin{:}); end function varargout = setMoveSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1853, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1936, self, varargin{:}); end function varargout = getRotateSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1854, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1937, self, varargin{:}); end function varargout = setRotateSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1855, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1938, self, varargin{:}); end function varargout = getZoomSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1856, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1939, self, varargin{:}); end function varargout = setZoomSpeed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1857, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1940, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1858, self); + iDynTreeMEX(1941, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/IEnvironment.m b/bindings/matlab/autogenerated/+iDynTree/IEnvironment.m index 2962ef1b3f..44400ff99b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IEnvironment.m +++ b/bindings/matlab/autogenerated/+iDynTree/IEnvironment.m @@ -5,36 +5,36 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1896, self); + iDynTreeMEX(1979, self); self.SwigClear(); end end function varargout = getElements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1897, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1980, self, varargin{:}); end function varargout = setElementVisibility(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1898, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1981, self, varargin{:}); end function varargout = setBackgroundColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1899, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1982, self, varargin{:}); end function varargout = setFloorGridColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1900, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1983, self, varargin{:}); end function varargout = setAmbientLight(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1901, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1984, self, varargin{:}); end function varargout = getLights(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1902, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1985, self, varargin{:}); end function varargout = addLight(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1903, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1986, self, varargin{:}); end function varargout = lightViz(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1904, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1987, self, varargin{:}); end function varargout = removeLight(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1905, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1988, self, varargin{:}); end function self = IEnvironment(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IFrameVisualization.m b/bindings/matlab/autogenerated/+iDynTree/IFrameVisualization.m index fbca1f076b..d8e193a13e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IFrameVisualization.m +++ b/bindings/matlab/autogenerated/+iDynTree/IFrameVisualization.m @@ -5,27 +5,27 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1935, self); + iDynTreeMEX(2018, self); self.SwigClear(); end end function varargout = addFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1936, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2019, self, varargin{:}); end function varargout = setVisible(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1937, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2020, self, varargin{:}); end function varargout = getNrOfFrames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1938, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2021, self, varargin{:}); end function varargout = getFrameTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1939, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2022, self, varargin{:}); end function varargout = updateFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1940, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2023, self, varargin{:}); end function varargout = getFrameLabel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1941, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2024, self, varargin{:}); end function self = IFrameVisualization(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IJetsVisualization.m b/bindings/matlab/autogenerated/+iDynTree/IJetsVisualization.m index aa0d61c1c1..26a4934d7e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IJetsVisualization.m +++ b/bindings/matlab/autogenerated/+iDynTree/IJetsVisualization.m @@ -5,30 +5,30 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1906, self); + iDynTreeMEX(1989, self); self.SwigClear(); end end function varargout = setJetsFrames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1907, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1990, self, varargin{:}); end function varargout = getNrOfJets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1908, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1991, self, varargin{:}); end function varargout = getJetDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1909, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1992, self, varargin{:}); end function varargout = setJetDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1910, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1993, self, varargin{:}); end function varargout = setJetColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1911, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1994, self, varargin{:}); end function varargout = setJetsDimensions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1912, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1995, self, varargin{:}); end function varargout = setJetsIntensity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1913, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1996, self, varargin{:}); end function self = IJetsVisualization(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IJoint.m b/bindings/matlab/autogenerated/+iDynTree/IJoint.m index 4e8645a17d..7d25879cb4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IJoint.m +++ b/bindings/matlab/autogenerated/+iDynTree/IJoint.m @@ -5,114 +5,132 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(791, self); + iDynTreeMEX(840, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(792, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(841, self, varargin{:}); end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(793, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(842, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(794, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(843, self, varargin{:}); end function varargout = setAttachedLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(795, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(844, self, varargin{:}); end function varargout = setRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(796, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(845, self, varargin{:}); end function varargout = getFirstAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(797, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(846, self, varargin{:}); end function varargout = getSecondAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(798, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(847, self, varargin{:}); end function varargout = getRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(799, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(848, self, varargin{:}); end function varargout = getTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(800, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(849, self, varargin{:}); end function varargout = getTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(801, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(850, self, varargin{:}); end function varargout = getMotionSubspaceVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(802, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(851, self, varargin{:}); end function varargout = computeChildPosVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(803, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(852, self, varargin{:}); end function varargout = computeChildVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(804, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(853, self, varargin{:}); end function varargout = computeChildVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(805, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(854, self, varargin{:}); end function varargout = computeChildAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(806, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(855, self, varargin{:}); end function varargout = computeChildBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(807, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(856, self, varargin{:}); end function varargout = computeJointTorque(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(808, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(857, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(809, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(858, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(810, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(859, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(811, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(860, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(812, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(861, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(813, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(862, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(814, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(863, self, varargin{:}); end function varargout = hasPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(815, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(864, self, varargin{:}); end function varargout = enablePosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(816, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(865, self, varargin{:}); end function varargout = getPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(817, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(866, self, varargin{:}); end function varargout = getMinPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(818, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(867, self, varargin{:}); end function varargout = getMaxPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(819, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(868, self, varargin{:}); end function varargout = setPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(820, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(869, self, varargin{:}); + end + function varargout = getJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(870, self, varargin{:}); + end + function varargout = setJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(871, self, varargin{:}); + end + function varargout = setDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(872, self, varargin{:}); + end + function varargout = setStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(873, self, varargin{:}); + end + function varargout = getDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(874, self, varargin{:}); + end + function varargout = getStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(875, self, varargin{:}); end function varargout = isRevoluteJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(821, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(876, self, varargin{:}); end function varargout = isFixedJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(822, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(877, self, varargin{:}); end function varargout = isPrismaticJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(823, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(878, self, varargin{:}); end function varargout = asRevoluteJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(824, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(879, self, varargin{:}); end function varargout = asFixedJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(825, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(880, self, varargin{:}); end function varargout = asPrismaticJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(826, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(881, self, varargin{:}); end function self = IJoint(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/ILabel.m b/bindings/matlab/autogenerated/+iDynTree/ILabel.m index 0d6b14ce03..08535caf2a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ILabel.m +++ b/bindings/matlab/autogenerated/+iDynTree/ILabel.m @@ -5,36 +5,36 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1914, self); + iDynTreeMEX(1997, self); self.SwigClear(); end end function varargout = setText(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1915, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1998, self, varargin{:}); end function varargout = getText(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1916, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1999, self, varargin{:}); end function varargout = setSize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1917, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2000, self, varargin{:}); end function varargout = width(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1918, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2001, self, varargin{:}); end function varargout = height(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1919, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2002, self, varargin{:}); end function varargout = setPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1920, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2003, self, varargin{:}); end function varargout = getPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1921, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2004, self, varargin{:}); end function varargout = setColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1922, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2005, self, varargin{:}); end function varargout = setVisible(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1923, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2006, self, varargin{:}); end function self = ILabel(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/ILight.m b/bindings/matlab/autogenerated/+iDynTree/ILight.m index 75536c6639..9bee492953 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ILight.m +++ b/bindings/matlab/autogenerated/+iDynTree/ILight.m @@ -5,48 +5,48 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1882, self); + iDynTreeMEX(1965, self); self.SwigClear(); end end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1883, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1966, self, varargin{:}); end function varargout = setType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1884, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1967, self, varargin{:}); end function varargout = getType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1885, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1968, self, varargin{:}); end function varargout = setPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1886, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1969, self, varargin{:}); end function varargout = getPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1887, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1970, self, varargin{:}); end function varargout = setDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1888, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1971, self, varargin{:}); end function varargout = getDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1889, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1972, self, varargin{:}); end function varargout = setAmbientColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1890, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1973, self, varargin{:}); end function varargout = getAmbientColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1891, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1974, self, varargin{:}); end function varargout = setSpecularColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1892, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1975, self, varargin{:}); end function varargout = getSpecularColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1893, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1976, self, varargin{:}); end function varargout = setDiffuseColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1894, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1977, self, varargin{:}); end function varargout = getDiffuseColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1895, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1978, self, varargin{:}); end function self = ILight(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IModelVisualization.m b/bindings/matlab/autogenerated/+iDynTree/IModelVisualization.m index 4d6e93c563..9108168bdf 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IModelVisualization.m +++ b/bindings/matlab/autogenerated/+iDynTree/IModelVisualization.m @@ -5,60 +5,60 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1942, self); + iDynTreeMEX(2025, self); self.SwigClear(); end end function varargout = setPositions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1943, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2026, self, varargin{:}); end function varargout = setLinkPositions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1944, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2027, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1945, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2028, self, varargin{:}); end function varargout = getInstanceName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1946, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2029, self, varargin{:}); end function varargout = setModelVisibility(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1947, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2030, self, varargin{:}); end function varargout = setModelColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1948, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2031, self, varargin{:}); end function varargout = resetModelColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1949, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2032, self, varargin{:}); end function varargout = setLinkColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1950, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2033, self, varargin{:}); end function varargout = resetLinkColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1951, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2034, self, varargin{:}); end function varargout = getLinkNames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1952, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2035, self, varargin{:}); end function varargout = setLinkVisibility(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1953, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2036, self, varargin{:}); end function varargout = getFeatures(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1954, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2037, self, varargin{:}); end function varargout = setFeatureVisibility(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1955, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2038, self, varargin{:}); end function varargout = jets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1956, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2039, self, varargin{:}); end function varargout = getWorldLinkTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1957, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2040, self, varargin{:}); end function varargout = getWorldFrameTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1958, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2041, self, varargin{:}); end function varargout = label(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1959, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2042, self, varargin{:}); end function self = IModelVisualization(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/INERTIAL_FIXED_REPRESENTATION.m b/bindings/matlab/autogenerated/+iDynTree/INERTIAL_FIXED_REPRESENTATION.m index dacb51f27a..53a2853084 100644 --- a/bindings/matlab/autogenerated/+iDynTree/INERTIAL_FIXED_REPRESENTATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/INERTIAL_FIXED_REPRESENTATION.m @@ -1,7 +1,7 @@ function v = INERTIAL_FIXED_REPRESENTATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 2); + vInitialized = iDynTreeMEX(0, 9); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/ITexture.m b/bindings/matlab/autogenerated/+iDynTree/ITexture.m index 6b98e68959..957fb554da 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ITexture.m +++ b/bindings/matlab/autogenerated/+iDynTree/ITexture.m @@ -5,33 +5,33 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1960, self); + iDynTreeMEX(2043, self); self.SwigClear(); end end function varargout = environment(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1961, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2044, self, varargin{:}); end function varargout = getPixelColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1962, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2045, self, varargin{:}); end function varargout = getPixels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1963, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2046, self, varargin{:}); end function varargout = drawToFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1964, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2047, self, varargin{:}); end function varargout = enableDraw(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1965, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2048, self, varargin{:}); end function varargout = width(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1966, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2049, self, varargin{:}); end function varargout = height(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1967, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2050, self, varargin{:}); end function varargout = setSubDrawArea(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1968, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2051, self, varargin{:}); end function self = ITexture(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/ITexturesHandler.m b/bindings/matlab/autogenerated/+iDynTree/ITexturesHandler.m index b2ec1b2132..c45b1cfc33 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ITexturesHandler.m +++ b/bindings/matlab/autogenerated/+iDynTree/ITexturesHandler.m @@ -5,15 +5,15 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1979, self); + iDynTreeMEX(2062, self); self.SwigClear(); end end function varargout = add(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1980, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2063, self, varargin{:}); end function varargout = get(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1981, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2064, self, varargin{:}); end function self = ITexturesHandler(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IVectorsVisualization.m b/bindings/matlab/autogenerated/+iDynTree/IVectorsVisualization.m index 390b36efe6..73831924cc 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IVectorsVisualization.m +++ b/bindings/matlab/autogenerated/+iDynTree/IVectorsVisualization.m @@ -5,39 +5,39 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1924, self); + iDynTreeMEX(2007, self); self.SwigClear(); end end function varargout = addVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1925, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2008, self, varargin{:}); end function varargout = getNrOfVectors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1926, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2009, self, varargin{:}); end function varargout = getVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1927, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2010, self, varargin{:}); end function varargout = updateVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1928, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2011, self, varargin{:}); end function varargout = setVectorColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1929, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2012, self, varargin{:}); end function varargout = setVectorsDefaultColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1930, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2013, self, varargin{:}); end function varargout = setVectorsColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1931, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2014, self, varargin{:}); end function varargout = setVectorsAspect(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1932, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2015, self, varargin{:}); end function varargout = setVisible(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1933, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2016, self, varargin{:}); end function varargout = getVectorLabel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1934, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2017, self, varargin{:}); end function self = IVectorsVisualization(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/IndexRange.m b/bindings/matlab/autogenerated/+iDynTree/IndexRange.m index 68fb6fbef2..ebd9cf5887 100644 --- a/bindings/matlab/autogenerated/+iDynTree/IndexRange.m +++ b/bindings/matlab/autogenerated/+iDynTree/IndexRange.m @@ -7,24 +7,24 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(123, self); + varargout{1} = iDynTreeMEX(198, self); else nargoutchk(0, 0) - iDynTreeMEX(124, self, varargin{1}); + iDynTreeMEX(199, self, varargin{1}); end end function varargout = size(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(125, self); + varargout{1} = iDynTreeMEX(200, self); else nargoutchk(0, 0) - iDynTreeMEX(126, self, varargin{1}); + iDynTreeMEX(201, self, varargin{1}); end end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(127, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(202, self, varargin{:}); end function self = IndexRange(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -32,21 +32,21 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(129, varargin{:}); + tmp = iDynTreeMEX(204, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(130, self); + iDynTreeMEX(205, self); self.SwigClear(); end end end methods(Static) function varargout = InvalidRange(varargin) - [varargout{1:nargout}] = iDynTreeMEX(128, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(203, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/IndexVector.m b/bindings/matlab/autogenerated/+iDynTree/IndexVector.m new file mode 100644 index 0000000000..7e0c59ef96 --- /dev/null +++ b/bindings/matlab/autogenerated/+iDynTree/IndexVector.m @@ -0,0 +1,95 @@ +classdef IndexVector < iDynTreeSwigRef + methods + function this = swig_this(self) + this = iDynTreeMEX(3, self); + end + function varargout = pop(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(121, self, varargin{:}); + end + function varargout = brace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(122, self, varargin{:}); + end + function varargout = setbrace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(123, self, varargin{:}); + end + function varargout = append(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(124, self, varargin{:}); + end + function varargout = empty(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(125, self, varargin{:}); + end + function varargout = size(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(126, self, varargin{:}); + end + function varargout = swap(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(127, self, varargin{:}); + end + function varargout = begin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(128, self, varargin{:}); + end + function varargout = end(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(129, self, varargin{:}); + end + function varargout = rbegin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(130, self, varargin{:}); + end + function varargout = rend(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(131, self, varargin{:}); + end + function varargout = clear(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(132, self, varargin{:}); + end + function varargout = get_allocator(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(133, self, varargin{:}); + end + function varargout = pop_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(134, self, varargin{:}); + end + function varargout = erase(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(135, self, varargin{:}); + end + function self = IndexVector(varargin) + if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') + if ~isnull(varargin{1}) + self.swigPtr = varargin{1}.swigPtr; + end + else + tmp = iDynTreeMEX(136, varargin{:}); + self.swigPtr = tmp.swigPtr; + tmp.SwigClear(); + end + end + function varargout = push_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(137, self, varargin{:}); + end + function varargout = front(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(138, self, varargin{:}); + end + function varargout = back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(139, self, varargin{:}); + end + function varargout = assign(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(140, self, varargin{:}); + end + function varargout = resize(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(141, self, varargin{:}); + end + function varargout = insert(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(142, self, varargin{:}); + end + function varargout = reserve(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(143, self, varargin{:}); + end + function varargout = capacity(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(144, self, varargin{:}); + end + function delete(self) + if self.swigPtr + iDynTreeMEX(145, self); + self.SwigClear(); + end + end + end + methods(Static) + end +end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseDynamicsInertialParametersRegressor.m b/bindings/matlab/autogenerated/+iDynTree/InverseDynamicsInertialParametersRegressor.m index eb3021be23..6998ba9ab4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseDynamicsInertialParametersRegressor.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseDynamicsInertialParametersRegressor.m @@ -1,3 +1,3 @@ function varargout = InverseDynamicsInertialParametersRegressor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1263, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1488, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematics.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematics.m index 9dd7d2ab66..ab709defeb 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematics.m @@ -9,187 +9,187 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(2053, varargin{:}); + tmp = iDynTreeMEX(2136, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(2054, self); + iDynTreeMEX(2137, self); self.SwigClear(); end end function varargout = loadModelFromFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2055, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2138, self, varargin{:}); end function varargout = setModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2056, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2139, self, varargin{:}); end function varargout = setJointLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2057, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2140, self, varargin{:}); end function varargout = getJointLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2058, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2141, self, varargin{:}); end function varargout = clearProblem(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2059, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2142, self, varargin{:}); end function varargout = setFloatingBaseOnFrameNamed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2060, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2143, self, varargin{:}); end function varargout = setCurrentRobotConfiguration(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2061, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2144, self, varargin{:}); end function varargout = setJointConfiguration(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2062, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2145, self, varargin{:}); end function varargout = setRotationParametrization(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2063, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2146, self, varargin{:}); end function varargout = rotationParametrization(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2064, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2147, self, varargin{:}); end function varargout = setMaxIterations(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2065, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2148, self, varargin{:}); end function varargout = maxIterations(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2066, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2149, self, varargin{:}); end function varargout = setMaxCPUTime(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2067, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2150, self, varargin{:}); end function varargout = maxCPUTime(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2068, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2151, self, varargin{:}); end function varargout = setCostTolerance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2069, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2152, self, varargin{:}); end function varargout = costTolerance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2070, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2153, self, varargin{:}); end function varargout = setConstraintsTolerance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2071, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2154, self, varargin{:}); end function varargout = constraintsTolerance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2072, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2155, self, varargin{:}); end function varargout = setVerbosity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2073, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2156, self, varargin{:}); end function varargout = linearSolverName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2074, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2157, self, varargin{:}); end function varargout = setLinearSolverName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2075, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2158, self, varargin{:}); end function varargout = addFrameConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2076, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2159, self, varargin{:}); end function varargout = addFramePositionConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2077, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2160, self, varargin{:}); end function varargout = addFrameRotationConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2078, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2161, self, varargin{:}); end function varargout = activateFrameConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2079, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2162, self, varargin{:}); end function varargout = deactivateFrameConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2080, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2163, self, varargin{:}); end function varargout = isFrameConstraintActive(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2081, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2164, self, varargin{:}); end function varargout = addCenterOfMassProjectionConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2082, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2165, self, varargin{:}); end function varargout = getCenterOfMassProjectionMargin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2083, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2166, self, varargin{:}); end function varargout = getCenterOfMassProjectConstraintConvexHull(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2084, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2167, self, varargin{:}); end function varargout = addTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2085, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2168, self, varargin{:}); end function varargout = addPositionTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2086, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2169, self, varargin{:}); end function varargout = addRotationTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2087, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2170, self, varargin{:}); end function varargout = updateTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2088, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2171, self, varargin{:}); end function varargout = updatePositionTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2089, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2172, self, varargin{:}); end function varargout = updateRotationTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2090, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2173, self, varargin{:}); end function varargout = setDefaultTargetResolutionMode(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2091, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2174, self, varargin{:}); end function varargout = defaultTargetResolutionMode(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2092, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2175, self, varargin{:}); end function varargout = setTargetResolutionMode(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2093, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2176, self, varargin{:}); end function varargout = targetResolutionMode(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2094, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2177, self, varargin{:}); end function varargout = setDesiredFullJointsConfiguration(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2095, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2178, self, varargin{:}); end function varargout = setDesiredReducedJointConfiguration(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2096, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2179, self, varargin{:}); end function varargout = setFullJointsInitialCondition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2097, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2180, self, varargin{:}); end function varargout = setReducedInitialCondition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2098, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2181, self, varargin{:}); end function varargout = solve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2099, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2182, self, varargin{:}); end function varargout = getFullJointsSolution(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2100, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2183, self, varargin{:}); end function varargout = getReducedSolution(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2101, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2184, self, varargin{:}); end function varargout = getPoseForFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2102, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2185, self, varargin{:}); end function varargout = fullModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2103, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2186, self, varargin{:}); end function varargout = reducedModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2104, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2187, self, varargin{:}); end function varargout = setCOMTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2105, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2188, self, varargin{:}); end function varargout = setCOMAsConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2106, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2189, self, varargin{:}); end function varargout = setCOMAsConstraintTolerance(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2107, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2190, self, varargin{:}); end function varargout = isCOMAConstraint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2108, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2191, self, varargin{:}); end function varargout = isCOMTargetActive(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2109, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2192, self, varargin{:}); end function varargout = deactivateCOMTarget(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2110, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2193, self, varargin{:}); end function varargout = setCOMConstraintProjectionDirection(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2111, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2194, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationQuaternion.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationQuaternion.m index 9c367c9730..b3899536d4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationQuaternion.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationQuaternion.m @@ -1,7 +1,7 @@ function v = InverseKinematicsRotationParametrizationQuaternion() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 36); + vInitialized = iDynTreeMEX(0, 38); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationRollPitchYaw.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationRollPitchYaw.m index a8da42f471..605cab5480 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationRollPitchYaw.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsRotationParametrizationRollPitchYaw.m @@ -1,7 +1,7 @@ function v = InverseKinematicsRotationParametrizationRollPitchYaw() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 37); + vInitialized = iDynTreeMEX(0, 39); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintFull.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintFull.m index 588d7c948c..0c1c40d56d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintFull.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintFull.m @@ -1,7 +1,7 @@ function v = InverseKinematicsTreatTargetAsConstraintFull() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 41); + vInitialized = iDynTreeMEX(0, 43); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintNone.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintNone.m index 0660b0c30a..ab2ea5bd8d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintNone.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintNone.m @@ -1,7 +1,7 @@ function v = InverseKinematicsTreatTargetAsConstraintNone() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 38); + vInitialized = iDynTreeMEX(0, 40); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintPositionOnly.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintPositionOnly.m index 072484827f..39fb2ba748 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintPositionOnly.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintPositionOnly.m @@ -1,7 +1,7 @@ function v = InverseKinematicsTreatTargetAsConstraintPositionOnly() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 39); + vInitialized = iDynTreeMEX(0, 41); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintRotationOnly.m b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintRotationOnly.m index c92f456b92..de3f9b709d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintRotationOnly.m +++ b/bindings/matlab/autogenerated/+iDynTree/InverseKinematicsTreatTargetAsConstraintRotationOnly.m @@ -1,7 +1,7 @@ function v = InverseKinematicsTreatTargetAsConstraintRotationOnly() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 40); + vInitialized = iDynTreeMEX(0, 42); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_INDEX.m b/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_INDEX.m index dae0e46db7..21fc53e0b2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_INDEX.m +++ b/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_INDEX.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(731); + varargout{1} = iDynTreeMEX(780); else nargoutchk(0,0) - iDynTreeMEX(732,varargin{1}); + iDynTreeMEX(781,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_NAME.m b/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_NAME.m index c0bc7ea6df..5bf0de4d39 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_NAME.m +++ b/bindings/matlab/autogenerated/+iDynTree/JOINT_INVALID_NAME.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(733); + varargout{1} = iDynTreeMEX(782); else nargoutchk(0,0) - iDynTreeMEX(734,varargin{1}); + iDynTreeMEX(783,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH.m b/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH.m index 4dfba73fe9..3c2cfaf540 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH.m +++ b/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH.m @@ -1,7 +1,7 @@ function v = JOINT_WRENCH() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 19); + vInitialized = iDynTreeMEX(0, 21); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH_SENSOR.m index 94c4604af5..7179a674bc 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/JOINT_WRENCH_SENSOR.m @@ -1,7 +1,7 @@ function v = JOINT_WRENCH_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 32); + vInitialized = iDynTreeMEX(0, 34); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/JointDOFsDoubleArray.m b/bindings/matlab/autogenerated/+iDynTree/JointDOFsDoubleArray.m index c77790359e..170b6380fe 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JointDOFsDoubleArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/JointDOFsDoubleArray.m @@ -7,20 +7,20 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1092, varargin{:}); + tmp = iDynTreeMEX(1223, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1093, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1224, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1094, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1225, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1095, self); + iDynTreeMEX(1226, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/JointPosDoubleArray.m b/bindings/matlab/autogenerated/+iDynTree/JointPosDoubleArray.m index 5936d020f9..660ca6553b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JointPosDoubleArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/JointPosDoubleArray.m @@ -7,20 +7,20 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1088, varargin{:}); + tmp = iDynTreeMEX(1219, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1089, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1220, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1090, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1221, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1091, self); + iDynTreeMEX(1222, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/JointSensor.m b/bindings/matlab/autogenerated/+iDynTree/JointSensor.m index e48c8d4f81..65e0613a15 100644 --- a/bindings/matlab/autogenerated/+iDynTree/JointSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/JointSensor.m @@ -2,24 +2,24 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1307, self); + iDynTreeMEX(1128, self); self.SwigClear(); end end function varargout = getParentJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1308, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1129, self, varargin{:}); end function varargout = getParentJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1309, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1130, self, varargin{:}); end function varargout = setParentJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1310, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1131, self, varargin{:}); end function varargout = setParentJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1311, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1132, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1312, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1133, self, varargin{:}); end function self = JointSensor(varargin) self@iDynTree.Sensor(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/KinDynComputations.m b/bindings/matlab/autogenerated/+iDynTree/KinDynComputations.m index aaf101698d..eb3d80866b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/KinDynComputations.m +++ b/bindings/matlab/autogenerated/+iDynTree/KinDynComputations.m @@ -9,178 +9,178 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1769, varargin{:}); + tmp = iDynTreeMEX(1852, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1770, self); + iDynTreeMEX(1853, self); self.SwigClear(); end end function varargout = loadRobotModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1771, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1854, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1772, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1855, self, varargin{:}); end function varargout = setFrameVelocityRepresentation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1773, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1856, self, varargin{:}); end function varargout = getFrameVelocityRepresentation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1774, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1857, self, varargin{:}); end function varargout = getNrOfDegreesOfFreedom(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1775, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1858, self, varargin{:}); end function varargout = getDescriptionOfDegreeOfFreedom(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1776, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1859, self, varargin{:}); end function varargout = getDescriptionOfDegreesOfFreedom(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1777, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1860, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1778, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1861, self, varargin{:}); end function varargout = getNrOfFrames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1779, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1862, self, varargin{:}); end function varargout = getFloatingBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1780, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1863, self, varargin{:}); end function varargout = setFloatingBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1781, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1864, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1782, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1865, self, varargin{:}); end function varargout = getRobotModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1783, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1866, self, varargin{:}); end function varargout = getRelativeJacobianSparsityPattern(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1784, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1867, self, varargin{:}); end function varargout = getFrameFreeFloatingJacobianSparsityPattern(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1785, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1868, self, varargin{:}); end function varargout = setJointPos(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1786, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1869, self, varargin{:}); end function varargout = setRobotState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1787, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1870, self, varargin{:}); end function varargout = getRobotState(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1788, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1871, self, varargin{:}); end function varargout = getWorldBaseTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1789, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1872, self, varargin{:}); end function varargout = getBaseTwist(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1790, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1873, self, varargin{:}); end function varargout = getJointPos(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1791, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1874, self, varargin{:}); end function varargout = getJointVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1792, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1875, self, varargin{:}); end function varargout = getModelVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1793, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1876, self, varargin{:}); end function varargout = getFrameIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1794, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1877, self, varargin{:}); end function varargout = getFrameName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1795, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1878, self, varargin{:}); end function varargout = getWorldTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1796, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1879, self, varargin{:}); end function varargout = getWorldTransformsAsHomogeneous(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1797, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1880, self, varargin{:}); end function varargout = getRelativeTransformExplicit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1798, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1881, self, varargin{:}); end function varargout = getRelativeTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1799, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1882, self, varargin{:}); end function varargout = getFrameVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1800, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1883, self, varargin{:}); end function varargout = getFrameAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1801, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1884, self, varargin{:}); end function varargout = getFrameFreeFloatingJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1802, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1885, self, varargin{:}); end function varargout = getRelativeJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1803, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1886, self, varargin{:}); end function varargout = getRelativeJacobianExplicit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1804, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1887, self, varargin{:}); end function varargout = getFrameBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1805, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1888, self, varargin{:}); end function varargout = getCenterOfMassPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1806, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1889, self, varargin{:}); end function varargout = getCenterOfMassVelocity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1807, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1890, self, varargin{:}); end function varargout = getCenterOfMassJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1808, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1891, self, varargin{:}); end function varargout = getCenterOfMassBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1809, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1892, self, varargin{:}); end function varargout = getAverageVelocity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1810, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1893, self, varargin{:}); end function varargout = getAverageVelocityJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1811, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1894, self, varargin{:}); end function varargout = getCentroidalAverageVelocity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1812, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1895, self, varargin{:}); end function varargout = getCentroidalAverageVelocityJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1813, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1896, self, varargin{:}); end function varargout = getLinearAngularMomentum(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1814, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1897, self, varargin{:}); end function varargout = getLinearAngularMomentumJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1815, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1898, self, varargin{:}); end function varargout = getCentroidalTotalMomentum(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1816, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1899, self, varargin{:}); end function varargout = getCentroidalTotalMomentumJacobian(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1817, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1900, self, varargin{:}); end function varargout = getFreeFloatingMassMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1818, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1901, self, varargin{:}); end function varargout = inverseDynamics(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1819, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1902, self, varargin{:}); end function varargout = inverseDynamicsWithInternalJointForceTorques(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1820, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1903, self, varargin{:}); end function varargout = generalizedBiasForces(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1821, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1904, self, varargin{:}); end function varargout = generalizedGravityForces(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1822, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1905, self, varargin{:}); end function varargout = generalizedExternalForces(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1823, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1906, self, varargin{:}); end function varargout = inverseDynamicsInertialParametersRegressor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1824, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1907, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_ACCELERATION.m b/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_ACCELERATION.m index c79622040b..8e9a91e949 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_ACCELERATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_ACCELERATION.m @@ -1,7 +1,7 @@ function v = LINK_BODY_PROPER_ACCELERATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 17); + vInitialized = iDynTreeMEX(0, 19); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_CLASSICAL_ACCELERATION.m b/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_CLASSICAL_ACCELERATION.m index 6416e4f88b..595c55441b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_CLASSICAL_ACCELERATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/LINK_BODY_PROPER_CLASSICAL_ACCELERATION.m @@ -1,7 +1,7 @@ function v = LINK_BODY_PROPER_CLASSICAL_ACCELERATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 23); + vInitialized = iDynTreeMEX(0, 25); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_INDEX.m b/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_INDEX.m index 3064051e4f..fe4f9fb06e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_INDEX.m +++ b/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_INDEX.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(727); + varargout{1} = iDynTreeMEX(776); else nargoutchk(0,0) - iDynTreeMEX(728,varargin{1}); + iDynTreeMEX(777,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_NAME.m b/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_NAME.m index 4fee8eaeb1..c17b83512b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_NAME.m +++ b/bindings/matlab/autogenerated/+iDynTree/LINK_INVALID_NAME.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(729); + varargout{1} = iDynTreeMEX(778); else nargoutchk(0,0) - iDynTreeMEX(730,varargin{1}); + iDynTreeMEX(779,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Link.m b/bindings/matlab/autogenerated/+iDynTree/Link.m index 718b7cccba..b1e82858e7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Link.m +++ b/bindings/matlab/autogenerated/+iDynTree/Link.m @@ -9,29 +9,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(784, varargin{:}); + tmp = iDynTreeMEX(833, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = inertia(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(785, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(834, self, varargin{:}); end function varargout = setInertia(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(786, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(835, self, varargin{:}); end function varargout = getInertia(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(787, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(836, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(788, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(837, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(789, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(838, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(790, self); + iDynTreeMEX(839, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkAccArray.m b/bindings/matlab/autogenerated/+iDynTree/LinkAccArray.m index 1a1651aeb3..64345a95af 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkAccArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkAccArray.m @@ -9,29 +9,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(777, varargin{:}); + tmp = iDynTreeMEX(826, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(778, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(827, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(779, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(828, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(780, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(829, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(781, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(830, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(782, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(831, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(783, self); + iDynTreeMEX(832, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkArticulatedBodyInertias.m b/bindings/matlab/autogenerated/+iDynTree/LinkArticulatedBodyInertias.m index 46d608ae55..630d0163be 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkArticulatedBodyInertias.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkArticulatedBodyInertias.m @@ -9,23 +9,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(765, varargin{:}); + tmp = iDynTreeMEX(814, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(766, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(815, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(767, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(816, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(768, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(817, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(769, self); + iDynTreeMEX(818, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkContactWrenches.m b/bindings/matlab/autogenerated/+iDynTree/LinkContactWrenches.m index 592a5e0b23..3ab64113ec 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkContactWrenches.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkContactWrenches.m @@ -9,35 +9,35 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1146, varargin{:}); + tmp = iDynTreeMEX(1277, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1147, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1278, self, varargin{:}); end function varargout = getNrOfContactsForLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1148, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1279, self, varargin{:}); end function varargout = setNrOfContactsForLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1149, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1280, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1150, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1281, self, varargin{:}); end function varargout = contactWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1151, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1282, self, varargin{:}); end function varargout = computeNetWrenches(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1152, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1283, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1153, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1284, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1154, self); + iDynTreeMEX(1285, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkInertias.m b/bindings/matlab/autogenerated/+iDynTree/LinkInertias.m index 637f98015e..4dcb462bcd 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkInertias.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkInertias.m @@ -9,23 +9,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(760, varargin{:}); + tmp = iDynTreeMEX(809, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(761, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(810, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(762, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(811, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(763, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(812, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(764, self); + iDynTreeMEX(813, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkPositions.m b/bindings/matlab/autogenerated/+iDynTree/LinkPositions.m index 184af7a26f..d0d80e13f5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkPositions.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkPositions.m @@ -9,29 +9,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(745, varargin{:}); + tmp = iDynTreeMEX(794, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(746, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(795, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(747, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(796, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(748, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(797, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(749, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(798, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(750, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(799, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(751, self); + iDynTreeMEX(800, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkSensor.m b/bindings/matlab/autogenerated/+iDynTree/LinkSensor.m index 63f25d99eb..ea8a4b00a1 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkSensor.m @@ -2,30 +2,30 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1313, self); + iDynTreeMEX(1134, self); self.SwigClear(); end end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1314, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1135, self, varargin{:}); end function varargout = getParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1315, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1136, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1316, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1137, self, varargin{:}); end function varargout = setParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1317, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1138, self, varargin{:}); end function varargout = setParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1318, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1139, self, varargin{:}); end function varargout = setLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1319, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1140, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1320, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1141, self, varargin{:}); end function self = LinkSensor(varargin) self@iDynTree.Sensor(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkUnknownWrenchContacts.m b/bindings/matlab/autogenerated/+iDynTree/LinkUnknownWrenchContacts.m index e8572f0d97..cad9c04565 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkUnknownWrenchContacts.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkUnknownWrenchContacts.m @@ -9,41 +9,41 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1500, varargin{:}); + tmp = iDynTreeMEX(1581, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1501, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1582, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1502, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1583, self, varargin{:}); end function varargout = getNrOfContactsForLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1503, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1584, self, varargin{:}); end function varargout = setNrOfContactsForLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1504, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1585, self, varargin{:}); end function varargout = addNewContactForLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1505, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1586, self, varargin{:}); end function varargout = addNewContactInFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1506, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1587, self, varargin{:}); end function varargout = addNewUnknownFullWrenchInFrameOrigin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1507, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1588, self, varargin{:}); end function varargout = contactWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1508, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1589, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1509, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1590, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1510, self); + iDynTreeMEX(1591, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkVelArray.m b/bindings/matlab/autogenerated/+iDynTree/LinkVelArray.m index 6a5892114a..fd7b7e6280 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkVelArray.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkVelArray.m @@ -9,29 +9,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(770, varargin{:}); + tmp = iDynTreeMEX(819, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(771, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(820, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(772, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(821, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(773, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(822, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(774, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(823, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(775, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(824, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(776, self); + iDynTreeMEX(825, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinkWrenches.m b/bindings/matlab/autogenerated/+iDynTree/LinkWrenches.m index de8b327db5..f982d2eb41 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinkWrenches.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinkWrenches.m @@ -9,32 +9,32 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(752, varargin{:}); + tmp = iDynTreeMEX(801, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(753, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(802, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(754, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(803, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(755, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(804, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(756, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(805, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(757, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(806, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(758, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(807, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(759, self); + iDynTreeMEX(808, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/LinksSolidShapesVector.m b/bindings/matlab/autogenerated/+iDynTree/LinksSolidShapesVector.m index 57904097f9..2483d966dd 100644 --- a/bindings/matlab/autogenerated/+iDynTree/LinksSolidShapesVector.m +++ b/bindings/matlab/autogenerated/+iDynTree/LinksSolidShapesVector.m @@ -4,49 +4,49 @@ this = iDynTreeMEX(3, self); end function varargout = pop(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1205, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1430, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1206, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1431, self, varargin{:}); end function varargout = setbrace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1207, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1432, self, varargin{:}); end function varargout = append(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1208, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1433, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1209, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1434, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1210, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1435, self, varargin{:}); end function varargout = swap(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1211, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1436, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1212, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1437, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1213, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1438, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1214, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1439, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1215, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1440, self, varargin{:}); end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1216, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1441, self, varargin{:}); end function varargout = get_allocator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1217, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1442, self, varargin{:}); end function varargout = pop_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1218, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1443, self, varargin{:}); end function varargout = erase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1219, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1444, self, varargin{:}); end function self = LinksSolidShapesVector(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -54,38 +54,38 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1220, varargin{:}); + tmp = iDynTreeMEX(1445, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = push_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1221, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1446, self, varargin{:}); end function varargout = front(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1222, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1447, self, varargin{:}); end function varargout = back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1223, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1448, self, varargin{:}); end function varargout = assign(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1224, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1449, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1225, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1450, self, varargin{:}); end function varargout = insert(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1226, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1451, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1227, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1452, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1228, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1453, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1229, self); + iDynTreeMEX(1454, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/MIXED_REPRESENTATION.m b/bindings/matlab/autogenerated/+iDynTree/MIXED_REPRESENTATION.m index e11655f9c8..fd87002642 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MIXED_REPRESENTATION.m +++ b/bindings/matlab/autogenerated/+iDynTree/MIXED_REPRESENTATION.m @@ -1,7 +1,7 @@ function v = MIXED_REPRESENTATION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 4); + vInitialized = iDynTreeMEX(0, 11); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/Material.m b/bindings/matlab/autogenerated/+iDynTree/Material.m index 700dcb981d..f571a0a635 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Material.m +++ b/bindings/matlab/autogenerated/+iDynTree/Material.m @@ -9,35 +9,35 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(979, varargin{:}); + tmp = iDynTreeMEX(1052, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = name(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(980, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1053, self, varargin{:}); end function varargout = hasColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(981, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1054, self, varargin{:}); end function varargout = color(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(982, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1055, self, varargin{:}); end function varargout = setColor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(983, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1056, self, varargin{:}); end function varargout = hasTexture(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(984, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1057, self, varargin{:}); end function varargout = texture(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(985, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1058, self, varargin{:}); end function varargout = setTexture(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(986, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1059, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(987, self); + iDynTreeMEX(1060, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix10x16.m b/bindings/matlab/autogenerated/+iDynTree/Matrix10x16.m index 64d67552e9..128778f10c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix10x16.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix10x16.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(299, varargin{:}); + tmp = iDynTreeMEX(374, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(300, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(375, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(301, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(376, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(302, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(377, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(303, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(378, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(304, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(379, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(305, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(380, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(306, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(381, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(307, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(382, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(308, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(383, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(309, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(384, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(310, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(385, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(311, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(386, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(312, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(387, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(313, self); + iDynTreeMEX(388, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix1x6.m b/bindings/matlab/autogenerated/+iDynTree/Matrix1x6.m index aac1d3eea4..7cec9efbe2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix1x6.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix1x6.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(209, varargin{:}); + tmp = iDynTreeMEX(284, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(210, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(285, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(211, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(286, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(212, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(287, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(213, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(288, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(214, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(289, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(215, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(290, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(216, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(291, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(217, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(292, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(218, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(293, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(219, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(294, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(220, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(295, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(221, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(296, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(222, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(297, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(223, self); + iDynTreeMEX(298, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix2x3.m b/bindings/matlab/autogenerated/+iDynTree/Matrix2x3.m index c2f8b9e337..006fcaa8ce 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix2x3.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix2x3.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(224, varargin{:}); + tmp = iDynTreeMEX(299, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(225, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(300, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(226, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(301, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(227, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(302, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(228, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(303, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(229, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(304, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(230, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(305, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(231, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(306, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(232, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(307, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(233, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(308, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(234, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(309, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(235, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(310, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(236, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(311, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(237, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(312, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(238, self); + iDynTreeMEX(313, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix3x3.m b/bindings/matlab/autogenerated/+iDynTree/Matrix3x3.m index 3a0a12bb9a..9c59adcc7e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix3x3.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix3x3.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(239, varargin{:}); + tmp = iDynTreeMEX(314, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(240, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(315, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(241, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(316, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(242, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(317, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(243, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(318, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(244, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(319, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(245, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(320, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(246, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(321, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(247, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(322, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(248, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(323, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(249, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(324, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(250, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(325, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(251, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(326, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(252, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(327, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(253, self); + iDynTreeMEX(328, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix4x4.m b/bindings/matlab/autogenerated/+iDynTree/Matrix4x4.m index 0a1e981224..d8be1698a3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix4x4.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix4x4.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(254, varargin{:}); + tmp = iDynTreeMEX(329, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(255, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(330, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(256, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(331, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(257, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(332, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(258, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(333, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(259, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(334, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(260, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(335, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(261, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(336, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(262, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(337, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(263, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(338, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(264, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(339, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(265, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(340, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(266, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(341, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(267, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(342, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(268, self); + iDynTreeMEX(343, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix4x4Vector.m b/bindings/matlab/autogenerated/+iDynTree/Matrix4x4Vector.m index 5affb36249..5e91844ed7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix4x4Vector.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix4x4Vector.m @@ -4,49 +4,49 @@ this = iDynTreeMEX(3, self); end function varargout = pop(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1825, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1908, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1826, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1909, self, varargin{:}); end function varargout = setbrace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1827, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1910, self, varargin{:}); end function varargout = append(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1828, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1911, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1829, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1912, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1830, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1913, self, varargin{:}); end function varargout = swap(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1831, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1914, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1832, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1915, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1833, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1916, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1834, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1917, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1835, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1918, self, varargin{:}); end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1836, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1919, self, varargin{:}); end function varargout = get_allocator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1837, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1920, self, varargin{:}); end function varargout = pop_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1838, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1921, self, varargin{:}); end function varargout = erase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1839, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1922, self, varargin{:}); end function self = Matrix4x4Vector(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -54,41 +54,41 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1840, varargin{:}); + tmp = iDynTreeMEX(1923, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = push_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1841, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1924, self, varargin{:}); end function varargout = front(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1842, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1925, self, varargin{:}); end function varargout = back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1843, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1926, self, varargin{:}); end function varargout = assign(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1844, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1927, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1845, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1928, self, varargin{:}); end function varargout = insert(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1846, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1929, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1847, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1930, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1848, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1931, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1849, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1932, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1850, self); + iDynTreeMEX(1933, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix6x10.m b/bindings/matlab/autogenerated/+iDynTree/Matrix6x10.m index 80df8e2c0f..fa8e7fc2fa 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix6x10.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix6x10.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(284, varargin{:}); + tmp = iDynTreeMEX(359, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(285, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(360, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(286, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(361, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(287, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(362, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(288, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(363, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(289, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(364, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(290, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(365, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(291, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(366, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(292, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(367, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(293, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(368, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(294, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(369, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(295, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(370, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(296, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(371, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(297, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(372, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(298, self); + iDynTreeMEX(373, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Matrix6x6.m b/bindings/matlab/autogenerated/+iDynTree/Matrix6x6.m index 6fec1f9a91..a312468b4f 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Matrix6x6.m +++ b/bindings/matlab/autogenerated/+iDynTree/Matrix6x6.m @@ -9,53 +9,53 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(269, varargin{:}); + tmp = iDynTreeMEX(344, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(270, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(345, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(271, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(346, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(272, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(347, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(273, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(348, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(274, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(349, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(275, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(350, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(276, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(351, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(277, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(352, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(278, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(353, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(279, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(354, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(280, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(355, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(281, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(356, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(282, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(357, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(283, self); + iDynTreeMEX(358, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/MatrixDynSize.m b/bindings/matlab/autogenerated/+iDynTree/MatrixDynSize.m index 6ab4166704..4097ce9d92 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MatrixDynSize.m +++ b/bindings/matlab/autogenerated/+iDynTree/MatrixDynSize.m @@ -9,67 +9,67 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(132, varargin{:}); + tmp = iDynTreeMEX(207, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(133, self); + iDynTreeMEX(208, self); self.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(134, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(209, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(135, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(210, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(136, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(211, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(137, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(212, self, varargin{:}); end function varargout = cols(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(138, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(213, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(139, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(214, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(140, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(215, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(141, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(216, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(142, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(217, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(143, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(218, self, varargin{:}); end function varargout = shrink_to_fit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(144, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(219, self, varargin{:}); end function varargout = fillRowMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(145, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(220, self, varargin{:}); end function varargout = fillColMajorBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(146, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(221, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(147, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(222, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(148, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(223, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(149, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(224, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(150, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(225, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/MatrixDynSizeVector.m b/bindings/matlab/autogenerated/+iDynTree/MatrixDynSizeVector.m new file mode 100644 index 0000000000..aa9333eaaa --- /dev/null +++ b/bindings/matlab/autogenerated/+iDynTree/MatrixDynSizeVector.m @@ -0,0 +1,95 @@ +classdef MatrixDynSizeVector < iDynTreeSwigRef + methods + function this = swig_this(self) + this = iDynTreeMEX(3, self); + end + function varargout = pop(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(71, self, varargin{:}); + end + function varargout = brace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(72, self, varargin{:}); + end + function varargout = setbrace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(73, self, varargin{:}); + end + function varargout = append(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(74, self, varargin{:}); + end + function varargout = empty(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(75, self, varargin{:}); + end + function varargout = size(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(76, self, varargin{:}); + end + function varargout = swap(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(77, self, varargin{:}); + end + function varargout = begin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(78, self, varargin{:}); + end + function varargout = end(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(79, self, varargin{:}); + end + function varargout = rbegin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(80, self, varargin{:}); + end + function varargout = rend(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(81, self, varargin{:}); + end + function varargout = clear(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(82, self, varargin{:}); + end + function varargout = get_allocator(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(83, self, varargin{:}); + end + function varargout = pop_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(84, self, varargin{:}); + end + function varargout = erase(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(85, self, varargin{:}); + end + function self = MatrixDynSizeVector(varargin) + if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') + if ~isnull(varargin{1}) + self.swigPtr = varargin{1}.swigPtr; + end + else + tmp = iDynTreeMEX(86, varargin{:}); + self.swigPtr = tmp.swigPtr; + tmp.SwigClear(); + end + end + function varargout = push_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(87, self, varargin{:}); + end + function varargout = front(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(88, self, varargin{:}); + end + function varargout = back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(89, self, varargin{:}); + end + function varargout = assign(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(90, self, varargin{:}); + end + function varargout = resize(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(91, self, varargin{:}); + end + function varargout = insert(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(92, self, varargin{:}); + end + function varargout = reserve(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(93, self, varargin{:}); + end + function varargout = capacity(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(94, self, varargin{:}); + end + function delete(self) + if self.swigPtr + iDynTreeMEX(95, self); + self.SwigClear(); + end + end + end + methods(Static) + end +end diff --git a/bindings/matlab/autogenerated/+iDynTree/Model.m b/bindings/matlab/autogenerated/+iDynTree/Model.m index ae4b33c946..4a3c68f94c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Model.m +++ b/bindings/matlab/autogenerated/+iDynTree/Model.m @@ -9,133 +9,145 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1047, varargin{:}); + tmp = iDynTreeMEX(1174, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = copy(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1048, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1175, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1049, self); + iDynTreeMEX(1176, self); self.SwigClear(); end end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1050, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1177, self, varargin{:}); + end + function varargout = getPackageDirs(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1178, self, varargin{:}); + end + function varargout = setPackageDirs(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1179, self, varargin{:}); end function varargout = getLinkName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1051, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1180, self, varargin{:}); end function varargout = getLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1052, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1181, self, varargin{:}); end function varargout = isValidLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1053, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1182, self, varargin{:}); end function varargout = getLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1054, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1183, self, varargin{:}); end function varargout = addLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1055, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1184, self, varargin{:}); end function varargout = getNrOfJoints(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1056, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1185, self, varargin{:}); end function varargout = getJointName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1057, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1186, self, varargin{:}); end function varargout = getTotalMass(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1058, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1187, self, varargin{:}); end function varargout = getJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1059, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1188, self, varargin{:}); end function varargout = getJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1060, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1189, self, varargin{:}); end function varargout = isValidJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1061, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1190, self, varargin{:}); end function varargout = isLinkNameUsed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1062, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1191, self, varargin{:}); end function varargout = isJointNameUsed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1063, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1192, self, varargin{:}); end function varargout = isFrameNameUsed(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1064, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1193, self, varargin{:}); end function varargout = addJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1065, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1194, self, varargin{:}); end function varargout = addJointAndLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1066, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1195, self, varargin{:}); end function varargout = insertLinkToExistingJointAndAddJointForDisplacedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1067, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1196, self, varargin{:}); end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1068, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1197, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1069, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1198, self, varargin{:}); end function varargout = getNrOfFrames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1070, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1199, self, varargin{:}); end function varargout = addAdditionalFrameToLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1071, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1200, self, varargin{:}); end function varargout = getFrameName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1072, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1201, self, varargin{:}); end function varargout = getFrameIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1073, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1202, self, varargin{:}); end function varargout = isValidFrameIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1074, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1203, self, varargin{:}); end function varargout = getFrameTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1075, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1204, self, varargin{:}); end function varargout = getFrameLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1076, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1205, self, varargin{:}); end function varargout = getLinkAdditionalFrames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1077, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1206, self, varargin{:}); end function varargout = getNrOfNeighbors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1078, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1207, self, varargin{:}); end function varargout = getNeighbor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1079, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1208, self, varargin{:}); end function varargout = setDefaultBaseLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1080, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1209, self, varargin{:}); end function varargout = getDefaultBaseLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1081, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1210, self, varargin{:}); end function varargout = computeFullTreeTraversal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1082, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1211, self, varargin{:}); end function varargout = getInertialParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1083, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1212, self, varargin{:}); end function varargout = updateInertialParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1084, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1213, self, varargin{:}); end function varargout = visualSolidShapes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1085, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1214, self, varargin{:}); end function varargout = collisionSolidShapes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1086, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1215, self, varargin{:}); + end + function varargout = sensors(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1216, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1087, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1217, self, varargin{:}); + end + function varargout = isValid(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1218, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelCalibrationHelper.m b/bindings/matlab/autogenerated/+iDynTree/ModelCalibrationHelper.m index 63453494cf..776e570257 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelCalibrationHelper.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelCalibrationHelper.m @@ -9,37 +9,37 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1479, varargin{:}); + tmp = iDynTreeMEX(1560, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1480, self); + iDynTreeMEX(1561, self); self.SwigClear(); end end function varargout = loadModelFromString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1481, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1562, self, varargin{:}); end function varargout = loadModelFromFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1482, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1563, self, varargin{:}); end function varargout = updateModelInertialParametersToString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1483, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1564, self, varargin{:}); end function varargout = updateModelInertialParametersToFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1484, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1565, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1485, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1566, self, varargin{:}); end function varargout = sensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1486, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1567, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1487, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1568, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelExporter.m b/bindings/matlab/autogenerated/+iDynTree/ModelExporter.m index f9f5387b6b..f029865633 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelExporter.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelExporter.m @@ -9,40 +9,40 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1469, varargin{:}); + tmp = iDynTreeMEX(1550, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1470, self); + iDynTreeMEX(1551, self); self.SwigClear(); end end function varargout = exportingOptions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1471, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1552, self, varargin{:}); end function varargout = setExportingOptions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1472, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1553, self, varargin{:}); end function varargout = init(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1473, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1554, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1474, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1555, self, varargin{:}); end function varargout = sensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1475, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1556, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1476, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1557, self, varargin{:}); end function varargout = exportModelToString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1477, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1558, self, varargin{:}); end function varargout = exportModelToFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1478, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1559, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelExporterOptions.m b/bindings/matlab/autogenerated/+iDynTree/ModelExporterOptions.m index 16e2b7cf50..a800952c4b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelExporterOptions.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelExporterOptions.m @@ -7,30 +7,40 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1461, self); + varargout{1} = iDynTreeMEX(1540, self); else nargoutchk(0, 0) - iDynTreeMEX(1462, self, varargin{1}); + iDynTreeMEX(1541, self, varargin{1}); end end function varargout = exportFirstBaseLinkAdditionalFrameAsFakeURDFBase(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1463, self); + varargout{1} = iDynTreeMEX(1542, self); else nargoutchk(0, 0) - iDynTreeMEX(1464, self, varargin{1}); + iDynTreeMEX(1543, self, varargin{1}); end end function varargout = robotExportedName(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1465, self); + varargout{1} = iDynTreeMEX(1544, self); else nargoutchk(0, 0) - iDynTreeMEX(1466, self, varargin{1}); + iDynTreeMEX(1545, self, varargin{1}); + end + end + function varargout = xmlBlobs(self, varargin) + narginchk(1, 2) + if nargin==1 + nargoutchk(0, 1) + varargout{1} = iDynTreeMEX(1546, self); + else + nargoutchk(0, 0) + iDynTreeMEX(1547, self, varargin{1}); end end function self = ModelExporterOptions(varargin) @@ -39,14 +49,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1467, varargin{:}); + tmp = iDynTreeMEX(1548, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1468, self); + iDynTreeMEX(1549, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelLoader.m b/bindings/matlab/autogenerated/+iDynTree/ModelLoader.m index 4e98329a21..9c655d0e34 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelLoader.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelLoader.m @@ -9,46 +9,46 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1449, varargin{:}); + tmp = iDynTreeMEX(1528, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1450, self); + iDynTreeMEX(1529, self); self.SwigClear(); end end function varargout = parsingOptions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1451, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1530, self, varargin{:}); end function varargout = setParsingOptions(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1452, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1531, self, varargin{:}); end function varargout = loadModelFromString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1453, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1532, self, varargin{:}); end function varargout = loadModelFromFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1454, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1533, self, varargin{:}); end function varargout = loadReducedModelFromFullModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1455, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1534, self, varargin{:}); end function varargout = loadReducedModelFromString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1456, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1535, self, varargin{:}); end function varargout = loadReducedModelFromFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1457, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1536, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1458, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1537, self, varargin{:}); end function varargout = sensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1459, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1538, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1460, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1539, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelParserOptions.m b/bindings/matlab/autogenerated/+iDynTree/ModelParserOptions.m index 3435ac5fb9..6cfe55079d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelParserOptions.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelParserOptions.m @@ -7,20 +7,20 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1443, self); + varargout{1} = iDynTreeMEX(1522, self); else nargoutchk(0, 0) - iDynTreeMEX(1444, self, varargin{1}); + iDynTreeMEX(1523, self, varargin{1}); end end function varargout = originalFilename(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1445, self); + varargout{1} = iDynTreeMEX(1524, self); else nargoutchk(0, 0) - iDynTreeMEX(1446, self, varargin{1}); + iDynTreeMEX(1525, self, varargin{1}); end end function self = ModelParserOptions(varargin) @@ -29,14 +29,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1447, varargin{:}); + tmp = iDynTreeMEX(1526, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1448, self); + iDynTreeMEX(1527, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ModelSolidShapes.m b/bindings/matlab/autogenerated/+iDynTree/ModelSolidShapes.m index b850b073c4..6ea0450875 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ModelSolidShapes.m +++ b/bindings/matlab/autogenerated/+iDynTree/ModelSolidShapes.m @@ -5,7 +5,7 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1035, self); + iDynTreeMEX(1110, self); self.SwigClear(); end end @@ -15,22 +15,22 @@ function delete(self) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1036, varargin{:}); + tmp = iDynTreeMEX(1111, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1037, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1112, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1038, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1113, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1039, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1114, self, varargin{:}); end function varargout = getLinkSolidShapes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1040, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1115, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/MomentumFreeFloatingJacobian.m b/bindings/matlab/autogenerated/+iDynTree/MomentumFreeFloatingJacobian.m index 4e621f5903..379516322d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MomentumFreeFloatingJacobian.m +++ b/bindings/matlab/autogenerated/+iDynTree/MomentumFreeFloatingJacobian.m @@ -7,20 +7,20 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1110, varargin{:}); + tmp = iDynTreeMEX(1241, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1111, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1242, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1112, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1243, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1113, self); + iDynTreeMEX(1244, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl1.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl1.m index 0aed39a031..40f0b8f9db 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl1.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl1.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(858, self); + iDynTreeMEX(919, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(859, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(920, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(860, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(921, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(861, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(922, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(862, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(923, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(863, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(924, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(864, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(925, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(865, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(926, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(866, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(927, self, varargin{:}); end function self = MovableJointImpl1(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl2.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl2.m index 6c4c17c437..91be6e0c1a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl2.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl2.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(867, self); + iDynTreeMEX(928, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(868, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(929, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(869, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(930, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(870, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(931, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(871, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(932, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(872, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(933, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(873, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(934, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(874, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(935, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(875, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(936, self, varargin{:}); end function self = MovableJointImpl2(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl3.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl3.m index 40aeceb953..0a19013d3a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl3.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl3.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(876, self); + iDynTreeMEX(937, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(877, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(938, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(878, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(939, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(879, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(940, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(880, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(941, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(881, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(942, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(882, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(943, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(883, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(944, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(884, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(945, self, varargin{:}); end function self = MovableJointImpl3(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl4.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl4.m index 7f9bfb062c..5c891de6bd 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl4.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl4.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(885, self); + iDynTreeMEX(946, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(886, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(947, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(887, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(948, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(888, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(949, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(889, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(950, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(890, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(951, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(891, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(952, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(892, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(953, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(893, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(954, self, varargin{:}); end function self = MovableJointImpl4(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl5.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl5.m index e1bdc0007b..24e5743af0 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl5.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl5.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(894, self); + iDynTreeMEX(955, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(895, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(956, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(896, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(957, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(897, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(958, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(898, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(959, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(899, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(960, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(900, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(961, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(901, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(962, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(902, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(963, self, varargin{:}); end function self = MovableJointImpl5(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl6.m b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl6.m index a732a993e1..7f5cf5a680 100644 --- a/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl6.m +++ b/bindings/matlab/autogenerated/+iDynTree/MovableJointImpl6.m @@ -2,33 +2,33 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(903, self); + iDynTreeMEX(964, self); self.SwigClear(); end end function varargout = getNrOfPosCoords(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(904, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(965, self, varargin{:}); end function varargout = getNrOfDOFs(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(905, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(966, self, varargin{:}); end function varargout = setIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(906, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(967, self, varargin{:}); end function varargout = getIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(907, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(968, self, varargin{:}); end function varargout = setPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(908, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(969, self, varargin{:}); end function varargout = getPosCoordsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(909, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(970, self, varargin{:}); end function varargout = setDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(910, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(971, self, varargin{:}); end function varargout = getDOFsOffset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(911, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(972, self, varargin{:}); end function self = MovableJointImpl6(varargin) self@iDynTree.IJoint(iDynTreeSwigRef.Null); diff --git a/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH.m b/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH.m index 25466be372..ec3981e4ea 100644 --- a/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH.m +++ b/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH.m @@ -1,7 +1,7 @@ function v = NET_EXT_WRENCH() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 21); + vInitialized = iDynTreeMEX(0, 23); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH_SENSOR.m index a601681591..9acf470778 100644 --- a/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/NET_EXT_WRENCH_SENSOR.m @@ -1,7 +1,7 @@ function v = NET_EXT_WRENCH_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 31); + vInitialized = iDynTreeMEX(0, 33); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV.m b/bindings/matlab/autogenerated/+iDynTree/NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV.m index c6947cffe6..425365699c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV.m +++ b/bindings/matlab/autogenerated/+iDynTree/NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV.m @@ -1,7 +1,7 @@ function v = NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 18); + vInitialized = iDynTreeMEX(0, 20); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/NO_UNKNOWNS.m b/bindings/matlab/autogenerated/+iDynTree/NO_UNKNOWNS.m index bae851ebcf..4a610c4092 100644 --- a/bindings/matlab/autogenerated/+iDynTree/NO_UNKNOWNS.m +++ b/bindings/matlab/autogenerated/+iDynTree/NO_UNKNOWNS.m @@ -1,7 +1,7 @@ function v = NO_UNKNOWNS() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 13); + vInitialized = iDynTreeMEX(0, 15); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/NR_OF_SENSOR_TYPES.m b/bindings/matlab/autogenerated/+iDynTree/NR_OF_SENSOR_TYPES.m index 8a7f595813..e2f33211eb 100644 --- a/bindings/matlab/autogenerated/+iDynTree/NR_OF_SENSOR_TYPES.m +++ b/bindings/matlab/autogenerated/+iDynTree/NR_OF_SENSOR_TYPES.m @@ -1,3 +1,3 @@ function v = NR_OF_SENSOR_TYPES() - v = iDynTreeMEX(1295); + v = iDynTreeMEX(1116); end diff --git a/bindings/matlab/autogenerated/+iDynTree/Neighbor.m b/bindings/matlab/autogenerated/+iDynTree/Neighbor.m index e4c9d910f3..70d5a60b24 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Neighbor.m +++ b/bindings/matlab/autogenerated/+iDynTree/Neighbor.m @@ -7,20 +7,20 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1041, self); + varargout{1} = iDynTreeMEX(1168, self); else nargoutchk(0, 0) - iDynTreeMEX(1042, self, varargin{1}); + iDynTreeMEX(1169, self, varargin{1}); end end function varargout = neighborJoint(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1043, self); + varargout{1} = iDynTreeMEX(1170, self); else nargoutchk(0, 0) - iDynTreeMEX(1044, self, varargin{1}); + iDynTreeMEX(1171, self, varargin{1}); end end function self = Neighbor(varargin) @@ -29,14 +29,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1045, varargin{:}); + tmp = iDynTreeMEX(1172, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1046, self); + iDynTreeMEX(1173, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/NoJointDynamics.m b/bindings/matlab/autogenerated/+iDynTree/NoJointDynamics.m new file mode 100644 index 0000000000..c0b30a1f81 --- /dev/null +++ b/bindings/matlab/autogenerated/+iDynTree/NoJointDynamics.m @@ -0,0 +1,7 @@ +function v = NoJointDynamics() + persistent vInitialized; + if isempty(vInitialized) + vInitialized = iDynTreeMEX(0, 2); + end + v = vInitialized; +end diff --git a/bindings/matlab/autogenerated/+iDynTree/ORIGINAL_BERDY_FIXED_BASE.m b/bindings/matlab/autogenerated/+iDynTree/ORIGINAL_BERDY_FIXED_BASE.m index 47cf14c7cc..d8acad6a85 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ORIGINAL_BERDY_FIXED_BASE.m +++ b/bindings/matlab/autogenerated/+iDynTree/ORIGINAL_BERDY_FIXED_BASE.m @@ -1,7 +1,7 @@ function v = ORIGINAL_BERDY_FIXED_BASE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 14); + vInitialized = iDynTreeMEX(0, 16); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/POINT_LIGHT.m b/bindings/matlab/autogenerated/+iDynTree/POINT_LIGHT.m index 3acd271f27..f04483b1d7 100644 --- a/bindings/matlab/autogenerated/+iDynTree/POINT_LIGHT.m +++ b/bindings/matlab/autogenerated/+iDynTree/POINT_LIGHT.m @@ -1,7 +1,7 @@ function v = POINT_LIGHT() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 34); + vInitialized = iDynTreeMEX(0, 36); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE.m b/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE.m index 0d9ecb64e3..3f6d14d179 100644 --- a/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE.m +++ b/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE.m @@ -1,7 +1,7 @@ function v = PURE_FORCE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 11); + vInitialized = iDynTreeMEX(0, 13); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE_WITH_KNOWN_DIRECTION.m b/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE_WITH_KNOWN_DIRECTION.m index 7bf6c36a94..56dc10333c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE_WITH_KNOWN_DIRECTION.m +++ b/bindings/matlab/autogenerated/+iDynTree/PURE_FORCE_WITH_KNOWN_DIRECTION.m @@ -1,7 +1,7 @@ function v = PURE_FORCE_WITH_KNOWN_DIRECTION() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 12); + vInitialized = iDynTreeMEX(0, 14); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/PixelViz.m b/bindings/matlab/autogenerated/+iDynTree/PixelViz.m index d2d0cf8efb..350b0416cd 100644 --- a/bindings/matlab/autogenerated/+iDynTree/PixelViz.m +++ b/bindings/matlab/autogenerated/+iDynTree/PixelViz.m @@ -4,20 +4,20 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1876, self); + varargout{1} = iDynTreeMEX(1959, self); else nargoutchk(0, 0) - iDynTreeMEX(1877, self, varargin{1}); + iDynTreeMEX(1960, self, varargin{1}); end end function varargout = height(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1878, self); + varargout{1} = iDynTreeMEX(1961, self); else nargoutchk(0, 0) - iDynTreeMEX(1879, self, varargin{1}); + iDynTreeMEX(1962, self, varargin{1}); end end function self = PixelViz(varargin) @@ -27,14 +27,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1880, varargin{:}); + tmp = iDynTreeMEX(1963, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1881, self); + iDynTreeMEX(1964, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Polygon.m b/bindings/matlab/autogenerated/+iDynTree/Polygon.m index 1762bc7b8e..6c4279ae72 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Polygon.m +++ b/bindings/matlab/autogenerated/+iDynTree/Polygon.m @@ -7,10 +7,10 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2006, self); + varargout{1} = iDynTreeMEX(2089, self); else nargoutchk(0, 0) - iDynTreeMEX(2007, self, varargin{1}); + iDynTreeMEX(2090, self, varargin{1}); end end function self = Polygon(varargin) @@ -19,36 +19,36 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(2008, varargin{:}); + tmp = iDynTreeMEX(2091, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = setNrOfVertices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2009, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2092, self, varargin{:}); end function varargout = getNrOfVertices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2010, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2093, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2011, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2094, self, varargin{:}); end function varargout = applyTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2012, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2095, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2013, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2096, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(2015, self); + iDynTreeMEX(2098, self); self.SwigClear(); end end end methods(Static) function varargout = XYRectangleFromOffsets(varargin) - [varargout{1:nargout}] = iDynTreeMEX(2014, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2097, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Polygon2D.m b/bindings/matlab/autogenerated/+iDynTree/Polygon2D.m index 69b3cf5661..e6bea5d9b5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Polygon2D.m +++ b/bindings/matlab/autogenerated/+iDynTree/Polygon2D.m @@ -7,10 +7,10 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(2016, self); + varargout{1} = iDynTreeMEX(2099, self); else nargoutchk(0, 0) - iDynTreeMEX(2017, self, varargin{1}); + iDynTreeMEX(2100, self, varargin{1}); end end function self = Polygon2D(varargin) @@ -19,26 +19,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(2018, varargin{:}); + tmp = iDynTreeMEX(2101, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = setNrOfVertices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2019, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2102, self, varargin{:}); end function varargout = getNrOfVertices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2020, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2103, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2021, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2104, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2022, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2105, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(2023, self); + iDynTreeMEX(2106, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Position.m b/bindings/matlab/autogenerated/+iDynTree/Position.m index b758749452..db0431d6d6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Position.m +++ b/bindings/matlab/autogenerated/+iDynTree/Position.m @@ -1,63 +1,63 @@ -classdef Position < iDynTree.PositionRaw +classdef Position < iDynTree.Vector3 methods function self = Position(varargin) - self@iDynTree.PositionRaw(iDynTreeSwigRef.Null); + self@iDynTree.Vector3(iDynTreeSwigRef.Null); if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') if ~isnull(varargin{1}) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(413, varargin{:}); + tmp = iDynTreeMEX(479, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = changePoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(414, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(480, self, varargin{:}); end function varargout = changeRefPoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(415, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(481, self, varargin{:}); end function varargout = changeCoordinateFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(416, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(482, self, varargin{:}); end function varargout = changePointOf(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(419, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(485, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(420, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(486, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(421, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(487, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(422, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(488, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(423, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(489, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(424, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(490, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(425, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(491, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(427, self); + iDynTreeMEX(493, self); self.SwigClear(); end end end methods(Static) function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(417, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(483, varargin{:}); end function varargout = inverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(418, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(484, varargin{:}); end function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(426, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(492, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/PositionRaw.m b/bindings/matlab/autogenerated/+iDynTree/PositionRaw.m deleted file mode 100644 index fc494eee01..0000000000 --- a/bindings/matlab/autogenerated/+iDynTree/PositionRaw.m +++ /dev/null @@ -1,45 +0,0 @@ -classdef PositionRaw < iDynTree.Vector3 - methods - function self = PositionRaw(varargin) - self@iDynTree.Vector3(iDynTreeSwigRef.Null); - if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') - if ~isnull(varargin{1}) - self.swigPtr = varargin{1}.swigPtr; - end - else - tmp = iDynTreeMEX(404, varargin{:}); - self.swigPtr = tmp.swigPtr; - tmp.SwigClear(); - end - end - function varargout = changePoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(405, self, varargin{:}); - end - function varargout = changeRefPoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(406, self, varargin{:}); - end - function varargout = changePointOf(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(409, self, varargin{:}); - end - function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(410, self, varargin{:}); - end - function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(411, self, varargin{:}); - end - function delete(self) - if self.swigPtr - iDynTreeMEX(412, self); - self.SwigClear(); - end - end - end - methods(Static) - function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(407, varargin{:}); - end - function varargout = inverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(408, varargin{:}); - end - end -end diff --git a/bindings/matlab/autogenerated/+iDynTree/PrismaticJoint.m b/bindings/matlab/autogenerated/+iDynTree/PrismaticJoint.m index 91fc7122e9..c679dd6b9e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/PrismaticJoint.m +++ b/bindings/matlab/autogenerated/+iDynTree/PrismaticJoint.m @@ -7,85 +7,103 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(937, varargin{:}); + tmp = iDynTreeMEX(1004, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(938, self); + iDynTreeMEX(1005, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(939, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1006, self, varargin{:}); end function varargout = setAttachedLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(940, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1007, self, varargin{:}); end function varargout = setRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(941, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1008, self, varargin{:}); end function varargout = setAxis(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(942, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1009, self, varargin{:}); end function varargout = getFirstAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(943, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1010, self, varargin{:}); end function varargout = getSecondAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(944, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1011, self, varargin{:}); end function varargout = getAxis(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(945, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1012, self, varargin{:}); end function varargout = getRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(946, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1013, self, varargin{:}); end function varargout = getTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(947, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1014, self, varargin{:}); end function varargout = getTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(948, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1015, self, varargin{:}); end function varargout = getMotionSubspaceVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(949, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1016, self, varargin{:}); end function varargout = computeChildPosVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(950, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1017, self, varargin{:}); end function varargout = computeChildVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(951, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1018, self, varargin{:}); end function varargout = computeChildVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(952, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1019, self, varargin{:}); end function varargout = computeChildAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(953, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1020, self, varargin{:}); end function varargout = computeChildBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(954, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1021, self, varargin{:}); end function varargout = computeJointTorque(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(955, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1022, self, varargin{:}); end function varargout = hasPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(956, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1023, self, varargin{:}); end function varargout = enablePosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(957, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1024, self, varargin{:}); end function varargout = getPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(958, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1025, self, varargin{:}); end function varargout = getMinPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(959, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1026, self, varargin{:}); end function varargout = getMaxPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(960, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1027, self, varargin{:}); end function varargout = setPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(961, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1028, self, varargin{:}); + end + function varargout = getJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1029, self, varargin{:}); + end + function varargout = setJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1030, self, varargin{:}); + end + function varargout = getDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1031, self, varargin{:}); + end + function varargout = getStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1032, self, varargin{:}); + end + function varargout = setDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1033, self, varargin{:}); + end + function varargout = setStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1034, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/RCM_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/RCM_SENSOR.m index 67e9eeba67..24a72f060b 100644 --- a/bindings/matlab/autogenerated/+iDynTree/RCM_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/RCM_SENSOR.m @@ -1,7 +1,7 @@ function v = RCM_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 33); + vInitialized = iDynTreeMEX(0, 35); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/RNEADynamicPhase.m b/bindings/matlab/autogenerated/+iDynTree/RNEADynamicPhase.m index 67af58279c..423462f4aa 100644 --- a/bindings/matlab/autogenerated/+iDynTree/RNEADynamicPhase.m +++ b/bindings/matlab/autogenerated/+iDynTree/RNEADynamicPhase.m @@ -1,3 +1,3 @@ function varargout = RNEADynamicPhase(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1238, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1463, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/RevoluteJoint.m b/bindings/matlab/autogenerated/+iDynTree/RevoluteJoint.m index ea4b848119..95f325c73d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/RevoluteJoint.m +++ b/bindings/matlab/autogenerated/+iDynTree/RevoluteJoint.m @@ -7,85 +7,103 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(912, varargin{:}); + tmp = iDynTreeMEX(973, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(913, self); + iDynTreeMEX(974, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(914, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(975, self, varargin{:}); end function varargout = setAttachedLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(915, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(976, self, varargin{:}); end function varargout = setRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(916, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(977, self, varargin{:}); end function varargout = setAxis(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(917, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(978, self, varargin{:}); end function varargout = getFirstAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(918, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(979, self, varargin{:}); end function varargout = getSecondAttachedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(919, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(980, self, varargin{:}); end function varargout = getAxis(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(920, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(981, self, varargin{:}); end function varargout = getRestTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(921, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(982, self, varargin{:}); end function varargout = getTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(922, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(983, self, varargin{:}); end function varargout = getTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(923, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(984, self, varargin{:}); end function varargout = getMotionSubspaceVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(924, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(985, self, varargin{:}); end function varargout = computeChildPosVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(925, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(986, self, varargin{:}); end function varargout = computeChildVel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(926, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(987, self, varargin{:}); end function varargout = computeChildVelAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(927, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(988, self, varargin{:}); end function varargout = computeChildAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(928, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(989, self, varargin{:}); end function varargout = computeChildBiasAcc(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(929, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(990, self, varargin{:}); end function varargout = computeJointTorque(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(930, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(991, self, varargin{:}); end function varargout = hasPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(931, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(992, self, varargin{:}); end function varargout = enablePosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(932, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(993, self, varargin{:}); end function varargout = getPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(933, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(994, self, varargin{:}); end function varargout = getMinPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(934, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(995, self, varargin{:}); end function varargout = getMaxPosLimit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(935, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(996, self, varargin{:}); end function varargout = setPosLimits(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(936, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(997, self, varargin{:}); + end + function varargout = getJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(998, self, varargin{:}); + end + function varargout = setJointDynamicsType(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(999, self, varargin{:}); + end + function varargout = getDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1000, self, varargin{:}); + end + function varargout = getStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1001, self, varargin{:}); + end + function varargout = setDamping(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1002, self, varargin{:}); + end + function varargout = setStaticFriction(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(1003, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/RigidBodyInertiaNonLinearParametrization.m b/bindings/matlab/autogenerated/+iDynTree/RigidBodyInertiaNonLinearParametrization.m index 14f3fb21ef..a009f34031 100644 --- a/bindings/matlab/autogenerated/+iDynTree/RigidBodyInertiaNonLinearParametrization.m +++ b/bindings/matlab/autogenerated/+iDynTree/RigidBodyInertiaNonLinearParametrization.m @@ -7,65 +7,65 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(600, self); + varargout{1} = iDynTreeMEX(663, self); else nargoutchk(0, 0) - iDynTreeMEX(601, self, varargin{1}); + iDynTreeMEX(664, self, varargin{1}); end end function varargout = com(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(602, self); + varargout{1} = iDynTreeMEX(665, self); else nargoutchk(0, 0) - iDynTreeMEX(603, self, varargin{1}); + iDynTreeMEX(666, self, varargin{1}); end end function varargout = link_R_centroidal(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(604, self); + varargout{1} = iDynTreeMEX(667, self); else nargoutchk(0, 0) - iDynTreeMEX(605, self, varargin{1}); + iDynTreeMEX(668, self, varargin{1}); end end function varargout = centralSecondMomentOfMass(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(606, self); + varargout{1} = iDynTreeMEX(669, self); else nargoutchk(0, 0) - iDynTreeMEX(607, self, varargin{1}); + iDynTreeMEX(670, self, varargin{1}); end end function varargout = getLinkCentroidalTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(608, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(671, self, varargin{:}); end function varargout = fromRigidBodyInertia(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(609, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(672, self, varargin{:}); end function varargout = fromInertialParameters(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(610, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(673, self, varargin{:}); end function varargout = toRigidBodyInertia(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(611, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(674, self, varargin{:}); end function varargout = isPhysicallyConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(612, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(675, self, varargin{:}); end function varargout = asVectorWithRotationAsVec(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(613, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(676, self, varargin{:}); end function varargout = fromVectorWithRotationAsVec(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(614, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(677, self, varargin{:}); end function varargout = getGradientWithRotationAsVec(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(615, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(678, self, varargin{:}); end function self = RigidBodyInertiaNonLinearParametrization(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -73,14 +73,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(616, varargin{:}); + tmp = iDynTreeMEX(679, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(617, self); + iDynTreeMEX(680, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Rotation.m b/bindings/matlab/autogenerated/+iDynTree/Rotation.m index 3b8d1f0218..6f023e75af 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Rotation.m +++ b/bindings/matlab/autogenerated/+iDynTree/Rotation.m @@ -1,120 +1,120 @@ -classdef Rotation < iDynTree.RotationRaw +classdef Rotation < iDynTree.Matrix3x3 methods function self = Rotation(varargin) - self@iDynTree.RotationRaw(iDynTreeSwigRef.Null); + self@iDynTree.Matrix3x3(iDynTreeSwigRef.Null); if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') if ~isnull(varargin{1}) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(632, varargin{:}); + tmp = iDynTreeMEX(681, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = changeOrientFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(633, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(682, self, varargin{:}); end function varargout = changeRefOrientFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(634, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(683, self, varargin{:}); end function varargout = changeCoordinateFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(635, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(684, self, varargin{:}); end function varargout = changeCoordFrameOf(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(638, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(687, self, varargin{:}); end function varargout = inverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(639, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(688, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(640, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(689, self, varargin{:}); end function varargout = log(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(641, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(690, self, varargin{:}); end function varargout = fromQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(642, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(691, self, varargin{:}); end function varargout = getRPY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(643, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(692, self, varargin{:}); end function varargout = asRPY(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(644, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(693, self, varargin{:}); end function varargout = getQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(645, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(694, self, varargin{:}); end function varargout = asQuaternion(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(646, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(695, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(663, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(712, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(664, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(713, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(665, self); + iDynTreeMEX(714, self); self.SwigClear(); end end end methods(Static) function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(636, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(685, varargin{:}); end function varargout = inverse2(varargin) - [varargout{1:nargout}] = iDynTreeMEX(637, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(686, varargin{:}); end function varargout = RotX(varargin) - [varargout{1:nargout}] = iDynTreeMEX(647, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(696, varargin{:}); end function varargout = RotY(varargin) - [varargout{1:nargout}] = iDynTreeMEX(648, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(697, varargin{:}); end function varargout = RotZ(varargin) - [varargout{1:nargout}] = iDynTreeMEX(649, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(698, varargin{:}); end function varargout = RotAxis(varargin) - [varargout{1:nargout}] = iDynTreeMEX(650, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(699, varargin{:}); end function varargout = RotAxisDerivative(varargin) - [varargout{1:nargout}] = iDynTreeMEX(651, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(700, varargin{:}); end function varargout = RPY(varargin) - [varargout{1:nargout}] = iDynTreeMEX(652, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(701, varargin{:}); end function varargout = RPYRightTrivializedDerivative(varargin) - [varargout{1:nargout}] = iDynTreeMEX(653, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(702, varargin{:}); end function varargout = RPYRightTrivializedDerivativeRateOfChange(varargin) - [varargout{1:nargout}] = iDynTreeMEX(654, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(703, varargin{:}); end function varargout = RPYRightTrivializedDerivativeInverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(655, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(704, varargin{:}); end function varargout = RPYRightTrivializedDerivativeInverseRateOfChange(varargin) - [varargout{1:nargout}] = iDynTreeMEX(656, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(705, varargin{:}); end function varargout = QuaternionRightTrivializedDerivative(varargin) - [varargout{1:nargout}] = iDynTreeMEX(657, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(706, varargin{:}); end function varargout = QuaternionRightTrivializedDerivativeInverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(658, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(707, varargin{:}); end function varargout = Identity(varargin) - [varargout{1:nargout}] = iDynTreeMEX(659, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(708, varargin{:}); end function varargout = RotationFromQuaternion(varargin) - [varargout{1:nargout}] = iDynTreeMEX(660, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(709, varargin{:}); end function varargout = leftJacobian(varargin) - [varargout{1:nargout}] = iDynTreeMEX(661, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(710, varargin{:}); end function varargout = leftJacobianInverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(662, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(711, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/RotationRaw.m b/bindings/matlab/autogenerated/+iDynTree/RotationRaw.m deleted file mode 100644 index e5a828e173..0000000000 --- a/bindings/matlab/autogenerated/+iDynTree/RotationRaw.m +++ /dev/null @@ -1,60 +0,0 @@ -classdef RotationRaw < iDynTree.Matrix3x3 - methods - function self = RotationRaw(varargin) - self@iDynTree.Matrix3x3(iDynTreeSwigRef.Null); - if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') - if ~isnull(varargin{1}) - self.swigPtr = varargin{1}.swigPtr; - end - else - tmp = iDynTreeMEX(618, varargin{:}); - self.swigPtr = tmp.swigPtr; - tmp.SwigClear(); - end - end - function varargout = changeOrientFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(619, self, varargin{:}); - end - function varargout = changeRefOrientFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(620, self, varargin{:}); - end - function varargout = changeCoordFrameOf(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(623, self, varargin{:}); - end - function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(629, self, varargin{:}); - end - function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(630, self, varargin{:}); - end - function delete(self) - if self.swigPtr - iDynTreeMEX(631, self); - self.SwigClear(); - end - end - end - methods(Static) - function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(621, varargin{:}); - end - function varargout = inverse2(varargin) - [varargout{1:nargout}] = iDynTreeMEX(622, varargin{:}); - end - function varargout = RotX(varargin) - [varargout{1:nargout}] = iDynTreeMEX(624, varargin{:}); - end - function varargout = RotY(varargin) - [varargout{1:nargout}] = iDynTreeMEX(625, varargin{:}); - end - function varargout = RotZ(varargin) - [varargout{1:nargout}] = iDynTreeMEX(626, varargin{:}); - end - function varargout = RPY(varargin) - [varargout{1:nargout}] = iDynTreeMEX(627, varargin{:}); - end - function varargout = Identity(varargin) - [varargout{1:nargout}] = iDynTreeMEX(628, varargin{:}); - end - end -end diff --git a/bindings/matlab/autogenerated/+iDynTree/RotationalInertiaRaw.m b/bindings/matlab/autogenerated/+iDynTree/RotationalInertia.m similarity index 66% rename from bindings/matlab/autogenerated/+iDynTree/RotationalInertiaRaw.m rename to bindings/matlab/autogenerated/+iDynTree/RotationalInertia.m index 8f79edd45b..c8a1f03d0c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/RotationalInertiaRaw.m +++ b/bindings/matlab/autogenerated/+iDynTree/RotationalInertia.m @@ -1,27 +1,27 @@ -classdef RotationalInertiaRaw < iDynTree.Matrix3x3 +classdef RotationalInertia < iDynTree.Matrix3x3 methods - function self = RotationalInertiaRaw(varargin) + function self = RotationalInertia(varargin) self@iDynTree.Matrix3x3(iDynTreeSwigRef.Null); if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') if ~isnull(varargin{1}) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(555, varargin{:}); + tmp = iDynTreeMEX(621, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(557, self); + iDynTreeMEX(623, self); self.SwigClear(); end end end methods(Static) function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(556, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(622, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE.m b/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE.m index 19276e5189..8d92e16885 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE.m +++ b/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE.m @@ -1,7 +1,7 @@ function v = SIX_AXIS_FORCE_TORQUE() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 5); + vInitialized = iDynTreeMEX(0, 4); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE_SENSOR.m index a2c93384fe..8bd9ce1c69 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/SIX_AXIS_FORCE_TORQUE_SENSOR.m @@ -1,7 +1,7 @@ function v = SIX_AXIS_FORCE_TORQUE_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 24); + vInitialized = iDynTreeMEX(0, 26); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/Sensor.m b/bindings/matlab/autogenerated/+iDynTree/Sensor.m index 65980309b5..741f4e2a28 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Sensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/Sensor.m @@ -5,30 +5,30 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(1299, self); + iDynTreeMEX(1120, self); self.SwigClear(); end end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1300, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1121, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1301, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1122, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1302, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1123, self, varargin{:}); end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1303, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1124, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1304, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1125, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1305, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1126, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1306, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1127, self, varargin{:}); end function self = Sensor(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/SensorsList.m b/bindings/matlab/autogenerated/+iDynTree/SensorsList.m index b39d0f6c72..148da703fe 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SensorsList.m +++ b/bindings/matlab/autogenerated/+iDynTree/SensorsList.m @@ -9,61 +9,61 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1321, varargin{:}); + tmp = iDynTreeMEX(1142, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1322, self); + iDynTreeMEX(1143, self); self.SwigClear(); end end function varargout = addSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1323, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1144, self, varargin{:}); end function varargout = setSerialization(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1324, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1145, self, varargin{:}); end function varargout = getSerialization(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1325, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1146, self, varargin{:}); end function varargout = getNrOfSensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1326, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1147, self, varargin{:}); end function varargout = getSensorIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1327, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1148, self, varargin{:}); end function varargout = getSizeOfAllSensorsMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1328, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1149, self, varargin{:}); end function varargout = getSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1329, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1150, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1330, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1151, self, varargin{:}); end function varargout = removeSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1331, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1152, self, varargin{:}); end function varargout = removeAllSensorsOfType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1332, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1153, self, varargin{:}); end function varargout = getSixAxisForceTorqueSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1333, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1154, self, varargin{:}); end function varargout = getAccelerometerSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1334, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1155, self, varargin{:}); end function varargout = getGyroscopeSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1335, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1156, self, varargin{:}); end function varargout = getThreeAxisAngularAccelerometerSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1336, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1157, self, varargin{:}); end function varargout = getThreeAxisForceTorqueContactSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1337, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1158, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/SensorsMeasurements.m b/bindings/matlab/autogenerated/+iDynTree/SensorsMeasurements.m index 4d39610c9d..f283a4b9a5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SensorsMeasurements.m +++ b/bindings/matlab/autogenerated/+iDynTree/SensorsMeasurements.m @@ -9,37 +9,37 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1338, varargin{:}); + tmp = iDynTreeMEX(1159, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1339, self); + iDynTreeMEX(1160, self); self.SwigClear(); end end function varargout = setNrOfSensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1340, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1161, self, varargin{:}); end function varargout = getNrOfSensors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1341, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1162, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1342, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1163, self, varargin{:}); end function varargout = toVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1343, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1164, self, varargin{:}); end function varargout = setMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1344, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1165, self, varargin{:}); end function varargout = getMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1345, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1166, self, varargin{:}); end function varargout = getSizeOfAllSensorsMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1346, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1167, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/SimpleLeggedOdometry.m b/bindings/matlab/autogenerated/+iDynTree/SimpleLeggedOdometry.m index d444f28418..bcba8ec652 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SimpleLeggedOdometry.m +++ b/bindings/matlab/autogenerated/+iDynTree/SimpleLeggedOdometry.m @@ -9,40 +9,40 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1547, varargin{:}); + tmp = iDynTreeMEX(1630, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1548, self); + iDynTreeMEX(1631, self); self.SwigClear(); end end function varargout = setModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1549, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1632, self, varargin{:}); end function varargout = model(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1550, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1633, self, varargin{:}); end function varargout = updateKinematics(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1551, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1634, self, varargin{:}); end function varargout = init(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1552, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1635, self, varargin{:}); end function varargout = changeFixedFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1553, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1636, self, varargin{:}); end function varargout = getCurrentFixedLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1554, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1637, self, varargin{:}); end function varargout = getWorldLinkTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1555, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1638, self, varargin{:}); end function varargout = getWorldFrameTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1556, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1639, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/SixAxisForceTorqueSensor.m b/bindings/matlab/autogenerated/+iDynTree/SixAxisForceTorqueSensor.m index 07c8d60252..c570f3ee2f 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SixAxisForceTorqueSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/SixAxisForceTorqueSensor.m @@ -7,97 +7,97 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1347, varargin{:}); + tmp = iDynTreeMEX(1311, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1348, self); + iDynTreeMEX(1312, self); self.SwigClear(); end end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1349, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1313, self, varargin{:}); end function varargout = setFirstLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1350, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1314, self, varargin{:}); end function varargout = setSecondLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1351, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1315, self, varargin{:}); end function varargout = getFirstLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1352, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1316, self, varargin{:}); end function varargout = getSecondLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1353, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1317, self, varargin{:}); end function varargout = setFirstLinkName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1354, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1318, self, varargin{:}); end function varargout = setSecondLinkName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1355, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1319, self, varargin{:}); end function varargout = getFirstLinkName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1356, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1320, self, varargin{:}); end function varargout = getSecondLinkName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1357, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1321, self, varargin{:}); end function varargout = setParentJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1358, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1322, self, varargin{:}); end function varargout = setParentJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1359, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1323, self, varargin{:}); end function varargout = setAppliedWrenchLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1360, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1324, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1361, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1325, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1362, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1326, self, varargin{:}); end function varargout = getParentJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1363, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1327, self, varargin{:}); end function varargout = getParentJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1364, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1328, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1365, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1329, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1366, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1330, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1367, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1331, self, varargin{:}); end function varargout = getAppliedWrenchLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1368, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1332, self, varargin{:}); end function varargout = isLinkAttachedToSensor(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1369, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1333, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1370, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1334, self, varargin{:}); end function varargout = getWrenchAppliedOnLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1371, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1335, self, varargin{:}); end function varargout = getWrenchAppliedOnLinkMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1372, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1336, self, varargin{:}); end function varargout = getWrenchAppliedOnLinkInverseMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1373, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1337, self, varargin{:}); end function varargout = predictMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1374, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1338, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1375, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1339, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/SolidShape.m b/bindings/matlab/autogenerated/+iDynTree/SolidShape.m index 9d059bd86c..570f65b186 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SolidShape.m +++ b/bindings/matlab/autogenerated/+iDynTree/SolidShape.m @@ -5,60 +5,60 @@ end function delete(self) if self.swigPtr - iDynTreeMEX(988, self); + iDynTreeMEX(1061, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(989, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1062, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(990, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1063, self, varargin{:}); end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(991, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1064, self, varargin{:}); end function varargout = isNameValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(992, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1065, self, varargin{:}); end function varargout = getLink_H_geometry(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(993, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1066, self, varargin{:}); end function varargout = setLink_H_geometry(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(994, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1067, self, varargin{:}); end function varargout = isMaterialSet(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(995, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1068, self, varargin{:}); end function varargout = getMaterial(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(996, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1069, self, varargin{:}); end function varargout = setMaterial(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(997, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1070, self, varargin{:}); end function varargout = isSphere(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(998, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1071, self, varargin{:}); end function varargout = isBox(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(999, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1072, self, varargin{:}); end function varargout = isCylinder(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1000, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1073, self, varargin{:}); end function varargout = isExternalMesh(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1001, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1074, self, varargin{:}); end function varargout = asSphere(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1002, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1075, self, varargin{:}); end function varargout = asBox(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1003, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1076, self, varargin{:}); end function varargout = asCylinder(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1004, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1077, self, varargin{:}); end function varargout = asExternalMesh(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1005, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1078, self, varargin{:}); end function self = SolidShape(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') diff --git a/bindings/matlab/autogenerated/+iDynTree/SolidShapesVector.m b/bindings/matlab/autogenerated/+iDynTree/SolidShapesVector.m index c10b355a50..a21568e009 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SolidShapesVector.m +++ b/bindings/matlab/autogenerated/+iDynTree/SolidShapesVector.m @@ -4,49 +4,49 @@ this = iDynTreeMEX(3, self); end function varargout = pop(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1180, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1405, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1181, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1406, self, varargin{:}); end function varargout = setbrace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1182, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1407, self, varargin{:}); end function varargout = append(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1183, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1408, self, varargin{:}); end function varargout = empty(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1184, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1409, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1185, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1410, self, varargin{:}); end function varargout = swap(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1186, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1411, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1187, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1412, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1188, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1413, self, varargin{:}); end function varargout = rbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1189, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1414, self, varargin{:}); end function varargout = rend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1190, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1415, self, varargin{:}); end function varargout = clear(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1191, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1416, self, varargin{:}); end function varargout = get_allocator(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1192, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1417, self, varargin{:}); end function varargout = pop_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1193, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1418, self, varargin{:}); end function varargout = erase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1194, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1419, self, varargin{:}); end function self = SolidShapesVector(varargin) if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') @@ -54,38 +54,38 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1195, varargin{:}); + tmp = iDynTreeMEX(1420, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = push_back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1196, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1421, self, varargin{:}); end function varargout = front(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1197, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1422, self, varargin{:}); end function varargout = back(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1198, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1423, self, varargin{:}); end function varargout = assign(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1199, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1424, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1200, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1425, self, varargin{:}); end function varargout = insert(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1201, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1426, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1202, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1427, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1203, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1428, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(1204, self); + iDynTreeMEX(1429, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SparseMatrixColMajor.m b/bindings/matlab/autogenerated/+iDynTree/SparseMatrixColMajor.m index c4adf9c8ae..4182c41194 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SparseMatrixColMajor.m +++ b/bindings/matlab/autogenerated/+iDynTree/SparseMatrixColMajor.m @@ -9,66 +9,66 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(169, varargin{:}); + tmp = iDynTreeMEX(244, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(170, self); + iDynTreeMEX(245, self); self.SwigClear(); end end function varargout = numberOfNonZeros(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(171, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(246, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(172, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(247, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(173, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(248, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(174, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(249, self, varargin{:}); end function varargout = setFromConstTriplets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(175, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(250, self, varargin{:}); end function varargout = setFromTriplets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(176, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(251, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(178, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(253, self, varargin{:}); end function varargout = getValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(179, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(254, self, varargin{:}); end function varargout = setValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(180, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(255, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(181, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(256, self, varargin{:}); end function varargout = columns(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(182, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(257, self, varargin{:}); end function varargout = description(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(183, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(258, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(184, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(259, self, varargin{:}); end function varargout = toMatlabDense(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(185, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(260, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(186, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(261, self, varargin{:}); end end methods(Static) function varargout = sparseMatrixFromTriplets(varargin) - [varargout{1:nargout}] = iDynTreeMEX(177, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(252, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SparseMatrixRowMajor.m b/bindings/matlab/autogenerated/+iDynTree/SparseMatrixRowMajor.m index 0d7d8f4e32..f04d9dd253 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SparseMatrixRowMajor.m +++ b/bindings/matlab/autogenerated/+iDynTree/SparseMatrixRowMajor.m @@ -9,66 +9,66 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(151, varargin{:}); + tmp = iDynTreeMEX(226, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(152, self); + iDynTreeMEX(227, self); self.SwigClear(); end end function varargout = numberOfNonZeros(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(153, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(228, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(154, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(229, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(155, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(230, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(156, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(231, self, varargin{:}); end function varargout = setFromConstTriplets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(157, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(232, self, varargin{:}); end function varargout = setFromTriplets(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(158, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(233, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(160, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(235, self, varargin{:}); end function varargout = getValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(161, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(236, self, varargin{:}); end function varargout = setValue(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(162, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(237, self, varargin{:}); end function varargout = rows(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(163, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(238, self, varargin{:}); end function varargout = columns(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(164, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(239, self, varargin{:}); end function varargout = description(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(165, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(240, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(166, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(241, self, varargin{:}); end function varargout = toMatlabDense(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(167, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(242, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(168, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(243, self, varargin{:}); end end methods(Static) function varargout = sparseMatrixFromTriplets(varargin) - [varargout{1:nargout}] = iDynTreeMEX(159, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(234, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialAcc.m b/bindings/matlab/autogenerated/+iDynTree/SpatialAcc.m index 2d0b297ac2..c339631a6e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialAcc.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialAcc.m @@ -7,23 +7,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(517, varargin{:}); + tmp = iDynTreeMEX(583, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(518, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(584, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(519, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(585, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(520, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(586, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(521, self); + iDynTreeMEX(587, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialForceVector.m b/bindings/matlab/autogenerated/+iDynTree/SpatialForceVector.m index 52b1f3c00e..f071d889e8 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialForceVector.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialForceVector.m @@ -7,19 +7,19 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(498, varargin{:}); + tmp = iDynTreeMEX(564, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(499, self); + iDynTreeMEX(565, self); self.SwigClear(); end end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(500, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(566, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialForceVectorBase.m b/bindings/matlab/autogenerated/+iDynTree/SpatialForceVectorBase.m index 1c216adb57..d6aa2ea3eb 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialForceVectorBase.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialForceVectorBase.m @@ -9,87 +9,87 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(464, varargin{:}); + tmp = iDynTreeMEX(530, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = getLinearVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(465, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(531, self, varargin{:}); end function varargout = getAngularVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(466, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(532, self, varargin{:}); end function varargout = setLinearVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(467, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(533, self, varargin{:}); end function varargout = setAngularVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(468, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(534, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(469, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(535, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(470, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(536, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(471, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(537, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(472, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(538, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(473, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(539, self, varargin{:}); end function varargout = changePoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(474, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(540, self, varargin{:}); end function varargout = changeCoordFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(475, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(541, self, varargin{:}); end function varargout = dot(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(478, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(544, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(479, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(545, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(480, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(546, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(481, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(547, self, varargin{:}); end function varargout = asVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(483, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(549, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(484, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(550, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(485, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(551, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(486, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(552, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(487, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(553, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(488, self); + iDynTreeMEX(554, self); self.SwigClear(); end end end methods(Static) function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(476, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(542, varargin{:}); end function varargout = inverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(477, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(543, varargin{:}); end function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(482, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(548, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialInertia.m b/bindings/matlab/autogenerated/+iDynTree/SpatialInertia.m index 54ed35646e..df0b1ee37d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialInertia.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialInertia.m @@ -1,69 +1,92 @@ -classdef SpatialInertia < iDynTree.SpatialInertiaRaw +classdef SpatialInertia < iDynTreeSwigRef methods + function this = swig_this(self) + this = iDynTreeMEX(3, self); + end function self = SpatialInertia(varargin) - self@iDynTree.SpatialInertiaRaw(iDynTreeSwigRef.Null); if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') if ~isnull(varargin{1}) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(568, varargin{:}); + tmp = iDynTreeMEX(624, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end + function varargout = fromRotationalInertiaWrtCenterOfMass(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(626, self, varargin{:}); + end + function varargout = getMass(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(627, self, varargin{:}); + end + function varargout = getCenterOfMass(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(628, self, varargin{:}); + end + function varargout = getRotationalInertiaWrtFrameOrigin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(629, self, varargin{:}); + end + function varargout = getRotationalInertiaWrtCenterOfMass(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(630, self, varargin{:}); + end + function varargout = multiply(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(631, self, varargin{:}); + end + function varargout = zero(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(632, self, varargin{:}); + end function varargout = asMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(570, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(633, self, varargin{:}); end function varargout = applyInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(571, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(634, self, varargin{:}); end function varargout = getInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(572, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(635, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(573, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(636, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(574, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(637, self, varargin{:}); end function varargout = biasWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(575, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(638, self, varargin{:}); end function varargout = biasWrenchDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(576, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(639, self, varargin{:}); end function varargout = asVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(578, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(641, self, varargin{:}); end function varargout = fromVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(579, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(642, self, varargin{:}); end function varargout = isPhysicallyConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(580, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(643, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(584, self); + iDynTreeMEX(647, self); self.SwigClear(); end end end methods(Static) function varargout = combine(varargin) - [varargout{1:nargout}] = iDynTreeMEX(569, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(625, varargin{:}); end function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(577, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(640, varargin{:}); end function varargout = momentumRegressor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(581, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(644, varargin{:}); end function varargout = momentumDerivativeRegressor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(582, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(645, varargin{:}); end function varargout = momentumDerivativeSlotineLiRegressor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(583, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(646, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialInertiaRaw.m b/bindings/matlab/autogenerated/+iDynTree/SpatialInertiaRaw.m deleted file mode 100644 index 35b0f8c4cb..0000000000 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialInertiaRaw.m +++ /dev/null @@ -1,50 +0,0 @@ -classdef SpatialInertiaRaw < iDynTreeSwigRef - methods - function this = swig_this(self) - this = iDynTreeMEX(3, self); - end - function self = SpatialInertiaRaw(varargin) - if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') - if ~isnull(varargin{1}) - self.swigPtr = varargin{1}.swigPtr; - end - else - tmp = iDynTreeMEX(558, varargin{:}); - self.swigPtr = tmp.swigPtr; - tmp.SwigClear(); - end - end - function varargout = fromRotationalInertiaWrtCenterOfMass(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(559, self, varargin{:}); - end - function varargout = getMass(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(560, self, varargin{:}); - end - function varargout = getCenterOfMass(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(561, self, varargin{:}); - end - function varargout = getRotationalInertiaWrtFrameOrigin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(562, self, varargin{:}); - end - function varargout = getRotationalInertiaWrtCenterOfMass(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(563, self, varargin{:}); - end - function varargout = multiply(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(565, self, varargin{:}); - end - function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(566, self, varargin{:}); - end - function delete(self) - if self.swigPtr - iDynTreeMEX(567, self); - self.SwigClear(); - end - end - end - methods(Static) - function varargout = combine(varargin) - [varargout{1:nargout}] = iDynTreeMEX(564, varargin{:}); - end - end -end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialMomentum.m b/bindings/matlab/autogenerated/+iDynTree/SpatialMomentum.m index 48b60c6290..09f1953ee2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialMomentum.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialMomentum.m @@ -7,23 +7,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(512, varargin{:}); + tmp = iDynTreeMEX(578, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(513, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(579, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(514, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(580, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(515, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(581, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(516, self); + iDynTreeMEX(582, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVector.m b/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVector.m index 455a5a0250..82aab366f4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVector.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVector.m @@ -7,29 +7,29 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(491, varargin{:}); + tmp = iDynTreeMEX(557, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(492, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(558, self, varargin{:}); end function varargout = cross(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(493, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(559, self, varargin{:}); end function varargout = asCrossProductMatrix(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(494, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(560, self, varargin{:}); end function varargout = asCrossProductMatrixWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(495, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(561, self, varargin{:}); end function varargout = exp(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(496, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(562, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(497, self); + iDynTreeMEX(563, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVectorBase.m b/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVectorBase.m index 0104b2eaf8..9354a2b754 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVectorBase.m +++ b/bindings/matlab/autogenerated/+iDynTree/SpatialMotionVectorBase.m @@ -9,87 +9,87 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(439, varargin{:}); + tmp = iDynTreeMEX(505, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = getLinearVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(440, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(506, self, varargin{:}); end function varargout = getAngularVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(441, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(507, self, varargin{:}); end function varargout = setLinearVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(442, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(508, self, varargin{:}); end function varargout = setAngularVec3(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(443, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(509, self, varargin{:}); end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(444, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(510, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(445, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(511, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(446, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(512, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(447, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(513, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(448, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(514, self, varargin{:}); end function varargout = changePoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(449, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(515, self, varargin{:}); end function varargout = changeCoordFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(450, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(516, self, varargin{:}); end function varargout = dot(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(453, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(519, self, varargin{:}); end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(454, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(520, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(455, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(521, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(456, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(522, self, varargin{:}); end function varargout = asVector(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(458, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(524, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(459, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(525, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(460, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(526, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(461, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(527, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(462, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(528, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(463, self); + iDynTreeMEX(529, self); self.SwigClear(); end end end methods(Static) function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(451, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(517, varargin{:}); end function varargout = inverse(varargin) - [varargout{1:nargout}] = iDynTreeMEX(452, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(518, varargin{:}); end function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(457, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(523, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Sphere.m b/bindings/matlab/autogenerated/+iDynTree/Sphere.m index 6bafa636e5..5293257e0d 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Sphere.m +++ b/bindings/matlab/autogenerated/+iDynTree/Sphere.m @@ -2,18 +2,18 @@ methods function delete(self) if self.swigPtr - iDynTreeMEX(1006, self); + iDynTreeMEX(1079, self); self.SwigClear(); end end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1007, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1080, self, varargin{:}); end function varargout = getRadius(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1008, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1081, self, varargin{:}); end function varargout = setRadius(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1009, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1082, self, varargin{:}); end function self = Sphere(varargin) self@iDynTree.SolidShape(iDynTreeSwigRef.Null); @@ -22,7 +22,7 @@ function delete(self) self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1010, varargin{:}); + tmp = iDynTreeMEX(1083, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end diff --git a/bindings/matlab/autogenerated/+iDynTree/SubModelDecomposition.m b/bindings/matlab/autogenerated/+iDynTree/SubModelDecomposition.m index 8bb552e2f4..64e5cf6b75 100644 --- a/bindings/matlab/autogenerated/+iDynTree/SubModelDecomposition.m +++ b/bindings/matlab/autogenerated/+iDynTree/SubModelDecomposition.m @@ -9,37 +9,37 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1169, varargin{:}); + tmp = iDynTreeMEX(1300, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1170, self); + iDynTreeMEX(1301, self); self.SwigClear(); end end function varargout = splitModelAlongJoints(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1171, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1302, self, varargin{:}); end function varargout = setNrOfSubModels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1172, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1303, self, varargin{:}); end function varargout = getNrOfSubModels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1173, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1304, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1174, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1305, self, varargin{:}); end function varargout = getTraversal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1175, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1306, self, varargin{:}); end function varargout = getSubModelOfLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1176, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1307, self, varargin{:}); end function varargout = getSubModelOfFrame(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1177, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1308, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER.m b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER.m index f7acc48197..1d08b19552 100644 --- a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER.m +++ b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER.m @@ -1,7 +1,7 @@ function v = THREE_AXIS_ANGULAR_ACCELEROMETER() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 8); + vInitialized = iDynTreeMEX(0, 7); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR.m index 57c05aef22..c189d00d35 100644 --- a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR.m @@ -1,7 +1,7 @@ function v = THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 27); + vInitialized = iDynTreeMEX(0, 29); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT.m b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT.m index 63dc317e19..ace409b0b3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT.m +++ b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT.m @@ -1,7 +1,7 @@ function v = THREE_AXIS_FORCE_TORQUE_CONTACT() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 9); + vInitialized = iDynTreeMEX(0, 8); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR.m b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR.m index c8c03bf198..4681c19b1c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR.m +++ b/bindings/matlab/autogenerated/+iDynTree/THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR.m @@ -1,7 +1,7 @@ function v = THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR() persistent vInitialized; if isempty(vInitialized) - vInitialized = iDynTreeMEX(0, 28); + vInitialized = iDynTreeMEX(0, 30); end v = vInitialized; end diff --git a/bindings/matlab/autogenerated/+iDynTree/TRAVERSAL_INVALID_INDEX.m b/bindings/matlab/autogenerated/+iDynTree/TRAVERSAL_INVALID_INDEX.m index 864526522e..d9ee505f7a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/TRAVERSAL_INVALID_INDEX.m +++ b/bindings/matlab/autogenerated/+iDynTree/TRAVERSAL_INVALID_INDEX.m @@ -2,9 +2,9 @@ narginchk(0,1) if nargin==0 nargoutchk(0,1) - varargout{1} = iDynTreeMEX(743); + varargout{1} = iDynTreeMEX(792); else nargoutchk(0,0) - iDynTreeMEX(744,varargin{1}); + iDynTreeMEX(793,varargin{1}); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/ThreeAxisAngularAccelerometerSensor.m b/bindings/matlab/autogenerated/+iDynTree/ThreeAxisAngularAccelerometerSensor.m index 5051b55cfd..fe92406651 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ThreeAxisAngularAccelerometerSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/ThreeAxisAngularAccelerometerSensor.m @@ -7,55 +7,55 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1406, varargin{:}); + tmp = iDynTreeMEX(1370, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1407, self); + iDynTreeMEX(1371, self); self.SwigClear(); end end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1408, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1372, self, varargin{:}); end function varargout = setLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1409, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1373, self, varargin{:}); end function varargout = setParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1410, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1374, self, varargin{:}); end function varargout = setParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1411, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1375, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1412, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1376, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1413, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1377, self, varargin{:}); end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1414, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1378, self, varargin{:}); end function varargout = getParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1415, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1379, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1416, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1380, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1417, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1381, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1418, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1382, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1419, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1383, self, varargin{:}); end function varargout = predictMeasurement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1420, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1384, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/ThreeAxisForceTorqueContactSensor.m b/bindings/matlab/autogenerated/+iDynTree/ThreeAxisForceTorqueContactSensor.m index 6444a3ae8a..f2882877b8 100644 --- a/bindings/matlab/autogenerated/+iDynTree/ThreeAxisForceTorqueContactSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/ThreeAxisForceTorqueContactSensor.m @@ -7,64 +7,64 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1421, varargin{:}); + tmp = iDynTreeMEX(1385, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1422, self); + iDynTreeMEX(1386, self); self.SwigClear(); end end function varargout = setName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1423, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1387, self, varargin{:}); end function varargout = setLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1424, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1388, self, varargin{:}); end function varargout = setParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1425, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1389, self, varargin{:}); end function varargout = setParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1426, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1390, self, varargin{:}); end function varargout = getName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1427, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1391, self, varargin{:}); end function varargout = getSensorType(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1428, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1392, self, varargin{:}); end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1429, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1393, self, varargin{:}); end function varargout = getParentLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1430, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1394, self, varargin{:}); end function varargout = getLinkSensorTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1431, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1395, self, varargin{:}); end function varargout = isValid(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1432, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1396, self, varargin{:}); end function varargout = clone(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1433, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1397, self, varargin{:}); end function varargout = updateIndices(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1434, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1398, self, varargin{:}); end function varargout = setLoadCellLocations(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1435, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1399, self, varargin{:}); end function varargout = getLoadCellLocations(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1436, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1400, self, varargin{:}); end function varargout = computeThreeAxisForceTorqueFromLoadCellMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1437, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1401, self, varargin{:}); end function varargout = computeCenterOfPressureFromLoadCellMeasurements(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1438, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1402, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/Transform.m b/bindings/matlab/autogenerated/+iDynTree/Transform.m index ef5fc8827c..78bd562682 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Transform.m +++ b/bindings/matlab/autogenerated/+iDynTree/Transform.m @@ -9,66 +9,66 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(666, varargin{:}); + tmp = iDynTreeMEX(715, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = fromHomogeneousTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(667, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(716, self, varargin{:}); end function varargout = getRotation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(668, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(717, self, varargin{:}); end function varargout = getPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(669, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(718, self, varargin{:}); end function varargout = setRotation(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(670, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(719, self, varargin{:}); end function varargout = setPosition(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(671, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(720, self, varargin{:}); end function varargout = inverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(674, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(723, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(675, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(724, self, varargin{:}); end function varargout = asHomogeneousTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(677, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(726, self, varargin{:}); end function varargout = asAdjointTransform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(678, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(727, self, varargin{:}); end function varargout = asAdjointTransformWrench(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(679, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(728, self, varargin{:}); end function varargout = log(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(680, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(729, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(681, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(730, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(682, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(731, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(683, self); + iDynTreeMEX(732, self); self.SwigClear(); end end end methods(Static) function varargout = compose(varargin) - [varargout{1:nargout}] = iDynTreeMEX(672, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(721, varargin{:}); end function varargout = inverse2(varargin) - [varargout{1:nargout}] = iDynTreeMEX(673, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(722, varargin{:}); end function varargout = Identity(varargin) - [varargout{1:nargout}] = iDynTreeMEX(676, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(725, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/TransformDerivative.m b/bindings/matlab/autogenerated/+iDynTree/TransformDerivative.m index d47bacb2da..ef5ad75c19 100644 --- a/bindings/matlab/autogenerated/+iDynTree/TransformDerivative.m +++ b/bindings/matlab/autogenerated/+iDynTree/TransformDerivative.m @@ -9,51 +9,51 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(684, varargin{:}); + tmp = iDynTreeMEX(733, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(685, self); + iDynTreeMEX(734, self); self.SwigClear(); end end function varargout = getRotationDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(686, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(735, self, varargin{:}); end function varargout = getPositionDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(687, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(736, self, varargin{:}); end function varargout = setRotationDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(688, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(737, self, varargin{:}); end function varargout = setPositionDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(689, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(738, self, varargin{:}); end function varargout = asHomogeneousTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(691, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(740, self, varargin{:}); end function varargout = asAdjointTransformDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(692, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(741, self, varargin{:}); end function varargout = asAdjointTransformWrenchDerivative(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(693, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(742, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(694, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(743, self, varargin{:}); end function varargout = derivativeOfInverse(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(695, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(744, self, varargin{:}); end function varargout = transform(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(696, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(745, self, varargin{:}); end end methods(Static) function varargout = Zero(varargin) - [varargout{1:nargout}] = iDynTreeMEX(690, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(739, varargin{:}); end end end diff --git a/bindings/matlab/autogenerated/+iDynTree/TransformFromDH.m b/bindings/matlab/autogenerated/+iDynTree/TransformFromDH.m index 18363b5c5c..686ee6f601 100644 --- a/bindings/matlab/autogenerated/+iDynTree/TransformFromDH.m +++ b/bindings/matlab/autogenerated/+iDynTree/TransformFromDH.m @@ -1,3 +1,3 @@ function varargout = TransformFromDH(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1292, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1517, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/TransformFromDHCraig1989.m b/bindings/matlab/autogenerated/+iDynTree/TransformFromDHCraig1989.m index be984f408d..4bc66b5a59 100644 --- a/bindings/matlab/autogenerated/+iDynTree/TransformFromDHCraig1989.m +++ b/bindings/matlab/autogenerated/+iDynTree/TransformFromDHCraig1989.m @@ -1,3 +1,3 @@ function varargout = TransformFromDHCraig1989(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1291, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1516, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/Traversal.m b/bindings/matlab/autogenerated/+iDynTree/Traversal.m index 8ecca34b80..b553447984 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Traversal.m +++ b/bindings/matlab/autogenerated/+iDynTree/Traversal.m @@ -9,61 +9,61 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(962, varargin{:}); + tmp = iDynTreeMEX(1035, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(963, self); + iDynTreeMEX(1036, self); self.SwigClear(); end end function varargout = getNrOfVisitedLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(964, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1037, self, varargin{:}); end function varargout = getLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(965, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1038, self, varargin{:}); end function varargout = getBaseLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(966, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1039, self, varargin{:}); end function varargout = getParentLink(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(967, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1040, self, varargin{:}); end function varargout = getParentJoint(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(968, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1041, self, varargin{:}); end function varargout = getParentLinkFromLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(969, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1042, self, varargin{:}); end function varargout = getParentJointFromLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(970, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1043, self, varargin{:}); end function varargout = getTraversalIndexFromLinkIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(971, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1044, self, varargin{:}); end function varargout = reset(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(972, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1045, self, varargin{:}); end function varargout = addTraversalBase(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(973, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1046, self, varargin{:}); end function varargout = addTraversalElement(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(974, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1047, self, varargin{:}); end function varargout = isParentOf(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(975, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1048, self, varargin{:}); end function varargout = getChildLinkIndexFromJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(976, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1049, self, varargin{:}); end function varargout = getParentLinkIndexFromJointIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(977, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1050, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(978, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1051, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/Twist.m b/bindings/matlab/autogenerated/+iDynTree/Twist.m index c4ee2db4f6..dcaa803b71 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Twist.m +++ b/bindings/matlab/autogenerated/+iDynTree/Twist.m @@ -7,26 +7,26 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(501, varargin{:}); + tmp = iDynTreeMEX(567, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(502, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(568, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(503, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(569, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(504, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(570, self, varargin{:}); end function varargout = mtimes(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(505, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(571, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(506, self); + iDynTreeMEX(572, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/URDFJointDynamics.m b/bindings/matlab/autogenerated/+iDynTree/URDFJointDynamics.m new file mode 100644 index 0000000000..d87979a05b --- /dev/null +++ b/bindings/matlab/autogenerated/+iDynTree/URDFJointDynamics.m @@ -0,0 +1,7 @@ +function v = URDFJointDynamics() + persistent vInitialized; + if isempty(vInitialized) + vInitialized = iDynTreeMEX(0, 3); + end + v = vInitialized; +end diff --git a/bindings/matlab/autogenerated/+iDynTree/UnknownWrenchContact.m b/bindings/matlab/autogenerated/+iDynTree/UnknownWrenchContact.m index 8e0be448a6..603a7a116e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/UnknownWrenchContact.m +++ b/bindings/matlab/autogenerated/+iDynTree/UnknownWrenchContact.m @@ -9,7 +9,7 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1488, varargin{:}); + tmp = iDynTreeMEX(1569, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end @@ -18,55 +18,55 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1489, self); + varargout{1} = iDynTreeMEX(1570, self); else nargoutchk(0, 0) - iDynTreeMEX(1490, self, varargin{1}); + iDynTreeMEX(1571, self, varargin{1}); end end function varargout = contactPoint(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1491, self); + varargout{1} = iDynTreeMEX(1572, self); else nargoutchk(0, 0) - iDynTreeMEX(1492, self, varargin{1}); + iDynTreeMEX(1573, self, varargin{1}); end end function varargout = forceDirection(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1493, self); + varargout{1} = iDynTreeMEX(1574, self); else nargoutchk(0, 0) - iDynTreeMEX(1494, self, varargin{1}); + iDynTreeMEX(1575, self, varargin{1}); end end function varargout = knownWrench(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1495, self); + varargout{1} = iDynTreeMEX(1576, self); else nargoutchk(0, 0) - iDynTreeMEX(1496, self, varargin{1}); + iDynTreeMEX(1577, self, varargin{1}); end end function varargout = contactId(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1497, self); + varargout{1} = iDynTreeMEX(1578, self); else nargoutchk(0, 0) - iDynTreeMEX(1498, self, varargin{1}); + iDynTreeMEX(1579, self, varargin{1}); end end function delete(self) if self.swigPtr - iDynTreeMEX(1499, self); + iDynTreeMEX(1580, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Vector10.m b/bindings/matlab/autogenerated/+iDynTree/Vector10.m index 2bb66a02d3..3bfafa1b18 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Vector10.m +++ b/bindings/matlab/autogenerated/+iDynTree/Vector10.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(368, varargin{:}); + tmp = iDynTreeMEX(443, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(369, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(444, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(370, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(445, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(371, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(446, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(372, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(447, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(373, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(448, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(374, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(449, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(375, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(450, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(376, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(451, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(377, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(452, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(378, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(453, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(379, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(454, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(380, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(455, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(381, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(456, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(382, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(457, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(383, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(458, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(384, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(459, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(385, self); + iDynTreeMEX(460, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Vector16.m b/bindings/matlab/autogenerated/+iDynTree/Vector16.m index c0170808b1..cdcb34fbe6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Vector16.m +++ b/bindings/matlab/autogenerated/+iDynTree/Vector16.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(386, varargin{:}); + tmp = iDynTreeMEX(461, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(387, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(462, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(388, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(463, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(389, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(464, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(390, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(465, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(391, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(466, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(392, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(467, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(393, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(468, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(394, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(469, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(395, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(470, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(396, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(471, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(397, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(472, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(398, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(473, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(399, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(474, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(400, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(475, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(401, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(476, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(402, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(477, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(403, self); + iDynTreeMEX(478, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Vector3.m b/bindings/matlab/autogenerated/+iDynTree/Vector3.m index 5e3fb51fbc..5f8bc00397 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Vector3.m +++ b/bindings/matlab/autogenerated/+iDynTree/Vector3.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(314, varargin{:}); + tmp = iDynTreeMEX(389, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(315, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(390, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(316, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(391, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(317, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(392, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(318, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(393, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(319, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(394, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(320, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(395, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(321, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(396, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(322, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(397, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(323, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(398, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(324, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(399, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(325, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(400, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(326, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(401, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(327, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(402, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(328, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(403, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(329, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(404, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(330, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(405, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(331, self); + iDynTreeMEX(406, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Vector4.m b/bindings/matlab/autogenerated/+iDynTree/Vector4.m index 513af6bd9f..ff9adaca57 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Vector4.m +++ b/bindings/matlab/autogenerated/+iDynTree/Vector4.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(332, varargin{:}); + tmp = iDynTreeMEX(407, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(333, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(408, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(334, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(409, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(335, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(410, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(336, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(411, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(337, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(412, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(338, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(413, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(339, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(414, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(340, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(415, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(341, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(416, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(342, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(417, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(343, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(418, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(344, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(419, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(345, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(420, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(346, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(421, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(347, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(422, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(348, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(423, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(349, self); + iDynTreeMEX(424, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Vector6.m b/bindings/matlab/autogenerated/+iDynTree/Vector6.m index 2f6845754c..a8749a4824 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Vector6.m +++ b/bindings/matlab/autogenerated/+iDynTree/Vector6.m @@ -9,62 +9,62 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(350, varargin{:}); + tmp = iDynTreeMEX(425, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(351, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(426, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(352, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(427, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(353, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(428, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(354, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(429, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(355, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(430, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(356, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(431, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(357, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(432, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(358, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(433, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(359, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(434, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(360, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(435, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(361, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(436, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(362, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(437, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(363, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(438, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(364, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(439, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(365, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(440, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(366, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(441, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(367, self); + iDynTreeMEX(442, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/VectorDynSize.m b/bindings/matlab/autogenerated/+iDynTree/VectorDynSize.m index 20d0c274cd..ee3f54f81e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/VectorDynSize.m +++ b/bindings/matlab/autogenerated/+iDynTree/VectorDynSize.m @@ -9,76 +9,76 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(187, varargin{:}); + tmp = iDynTreeMEX(262, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(188, self); + iDynTreeMEX(263, self); self.SwigClear(); end end function varargout = paren(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(189, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(264, self, varargin{:}); end function varargout = brace(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(190, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(265, self, varargin{:}); end function varargout = getVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(191, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(266, self, varargin{:}); end function varargout = setVal(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(192, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(267, self, varargin{:}); end function varargout = cbegin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(193, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(268, self, varargin{:}); end function varargout = cend(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(194, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(269, self, varargin{:}); end function varargout = begin(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(195, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(270, self, varargin{:}); end function varargout = end(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(196, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(271, self, varargin{:}); end function varargout = size(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(197, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(272, self, varargin{:}); end function varargout = data(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(198, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(273, self, varargin{:}); end function varargout = zero(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(199, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(274, self, varargin{:}); end function varargout = reserve(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(200, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(275, self, varargin{:}); end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(201, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(276, self, varargin{:}); end function varargout = shrink_to_fit(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(202, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(277, self, varargin{:}); end function varargout = capacity(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(203, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(278, self, varargin{:}); end function varargout = fillBuffer(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(204, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(279, self, varargin{:}); end function varargout = toString(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(205, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(280, self, varargin{:}); end function varargout = display(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(206, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(281, self, varargin{:}); end function varargout = toMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(207, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(282, self, varargin{:}); end function varargout = fromMatlab(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(208, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(283, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/VectorDynSizeVector.m b/bindings/matlab/autogenerated/+iDynTree/VectorDynSizeVector.m new file mode 100644 index 0000000000..ec26a5d3bd --- /dev/null +++ b/bindings/matlab/autogenerated/+iDynTree/VectorDynSizeVector.m @@ -0,0 +1,95 @@ +classdef VectorDynSizeVector < iDynTreeSwigRef + methods + function this = swig_this(self) + this = iDynTreeMEX(3, self); + end + function varargout = pop(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(96, self, varargin{:}); + end + function varargout = brace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(97, self, varargin{:}); + end + function varargout = setbrace(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(98, self, varargin{:}); + end + function varargout = append(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(99, self, varargin{:}); + end + function varargout = empty(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(100, self, varargin{:}); + end + function varargout = size(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(101, self, varargin{:}); + end + function varargout = swap(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(102, self, varargin{:}); + end + function varargout = begin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(103, self, varargin{:}); + end + function varargout = end(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(104, self, varargin{:}); + end + function varargout = rbegin(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(105, self, varargin{:}); + end + function varargout = rend(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(106, self, varargin{:}); + end + function varargout = clear(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(107, self, varargin{:}); + end + function varargout = get_allocator(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(108, self, varargin{:}); + end + function varargout = pop_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(109, self, varargin{:}); + end + function varargout = erase(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(110, self, varargin{:}); + end + function self = VectorDynSizeVector(varargin) + if nargin==1 && strcmp(class(varargin{1}),'iDynTreeSwigRef') + if ~isnull(varargin{1}) + self.swigPtr = varargin{1}.swigPtr; + end + else + tmp = iDynTreeMEX(111, varargin{:}); + self.swigPtr = tmp.swigPtr; + tmp.SwigClear(); + end + end + function varargout = push_back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(112, self, varargin{:}); + end + function varargout = front(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(113, self, varargin{:}); + end + function varargout = back(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(114, self, varargin{:}); + end + function varargout = assign(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(115, self, varargin{:}); + end + function varargout = resize(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(116, self, varargin{:}); + end + function varargout = insert(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(117, self, varargin{:}); + end + function varargout = reserve(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(118, self, varargin{:}); + end + function varargout = capacity(self,varargin) + [varargout{1:nargout}] = iDynTreeMEX(119, self, varargin{:}); + end + function delete(self) + if self.swigPtr + iDynTreeMEX(120, self); + self.SwigClear(); + end + end + end + methods(Static) + end +end diff --git a/bindings/matlab/autogenerated/+iDynTree/Visualizer.m b/bindings/matlab/autogenerated/+iDynTree/Visualizer.m index 68de13a67c..eaa11e1a71 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Visualizer.m +++ b/bindings/matlab/autogenerated/+iDynTree/Visualizer.m @@ -9,82 +9,82 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1982, varargin{:}); + tmp = iDynTreeMEX(2065, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1983, self); + iDynTreeMEX(2066, self); self.SwigClear(); end end function varargout = init(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1984, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2067, self, varargin{:}); end function varargout = getNrOfVisualizedModels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1985, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2068, self, varargin{:}); end function varargout = getModelInstanceName(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1986, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2069, self, varargin{:}); end function varargout = getModelInstanceIndex(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1987, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2070, self, varargin{:}); end function varargout = addModel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1988, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2071, self, varargin{:}); end function varargout = modelViz(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1989, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2072, self, varargin{:}); end function varargout = camera(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1990, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2073, self, varargin{:}); end function varargout = enviroment(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1991, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2074, self, varargin{:}); end function varargout = environment(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1992, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2075, self, varargin{:}); end function varargout = vectors(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1993, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2076, self, varargin{:}); end function varargout = frames(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1994, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2077, self, varargin{:}); end function varargout = textures(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1995, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2078, self, varargin{:}); end function varargout = getLabel(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1996, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2079, self, varargin{:}); end function varargout = width(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1997, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2080, self, varargin{:}); end function varargout = height(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1998, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2081, self, varargin{:}); end function varargout = run(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1999, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2082, self, varargin{:}); end function varargout = draw(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2000, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2083, self, varargin{:}); end function varargout = subDraw(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2001, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2084, self, varargin{:}); end function varargout = drawToFile(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2002, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2085, self, varargin{:}); end function varargout = close(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2003, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2086, self, varargin{:}); end function varargout = isWindowActive(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2004, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2087, self, varargin{:}); end function varargout = setColorPalette(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(2005, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2088, self, varargin{:}); end end methods(Static) diff --git a/bindings/matlab/autogenerated/+iDynTree/VisualizerOptions.m b/bindings/matlab/autogenerated/+iDynTree/VisualizerOptions.m index 109dd236a2..f5b9dc59d3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/VisualizerOptions.m +++ b/bindings/matlab/autogenerated/+iDynTree/VisualizerOptions.m @@ -7,40 +7,40 @@ narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1969, self); + varargout{1} = iDynTreeMEX(2052, self); else nargoutchk(0, 0) - iDynTreeMEX(1970, self, varargin{1}); + iDynTreeMEX(2053, self, varargin{1}); end end function varargout = winWidth(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1971, self); + varargout{1} = iDynTreeMEX(2054, self); else nargoutchk(0, 0) - iDynTreeMEX(1972, self, varargin{1}); + iDynTreeMEX(2055, self, varargin{1}); end end function varargout = winHeight(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1973, self); + varargout{1} = iDynTreeMEX(2056, self); else nargoutchk(0, 0) - iDynTreeMEX(1974, self, varargin{1}); + iDynTreeMEX(2057, self, varargin{1}); end end function varargout = rootFrameArrowsDimension(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1975, self); + varargout{1} = iDynTreeMEX(2058, self); else nargoutchk(0, 0) - iDynTreeMEX(1976, self, varargin{1}); + iDynTreeMEX(2059, self, varargin{1}); end end function self = VisualizerOptions(varargin) @@ -49,14 +49,14 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1977, varargin{:}); + tmp = iDynTreeMEX(2060, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function delete(self) if self.swigPtr - iDynTreeMEX(1978, self); + iDynTreeMEX(2061, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/Wrench.m b/bindings/matlab/autogenerated/+iDynTree/Wrench.m index 918a01d1f1..137e985bb6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/Wrench.m +++ b/bindings/matlab/autogenerated/+iDynTree/Wrench.m @@ -7,23 +7,23 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(507, varargin{:}); + tmp = iDynTreeMEX(573, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = plus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(508, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(574, self, varargin{:}); end function varargout = minus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(509, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(575, self, varargin{:}); end function varargout = uminus(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(510, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(576, self, varargin{:}); end function delete(self) if self.swigPtr - iDynTreeMEX(511, self); + iDynTreeMEX(577, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/addRandomAdditionalFrameToModel.m b/bindings/matlab/autogenerated/+iDynTree/addRandomAdditionalFrameToModel.m index e0ba1d0b7a..88880efc21 100644 --- a/bindings/matlab/autogenerated/+iDynTree/addRandomAdditionalFrameToModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/addRandomAdditionalFrameToModel.m @@ -1,3 +1,3 @@ function varargout = addRandomAdditionalFrameToModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1157, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1288, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/addRandomLinkToModel.m b/bindings/matlab/autogenerated/+iDynTree/addRandomLinkToModel.m index b6a9e50d2f..a0f5bea660 100644 --- a/bindings/matlab/autogenerated/+iDynTree/addRandomLinkToModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/addRandomLinkToModel.m @@ -1,3 +1,3 @@ function varargout = addRandomLinkToModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1156, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1287, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/checkDoublesAreEqual.m b/bindings/matlab/autogenerated/+iDynTree/checkDoublesAreEqual.m index 2eac6442be..b4691f25a6 100644 --- a/bindings/matlab/autogenerated/+iDynTree/checkDoublesAreEqual.m +++ b/bindings/matlab/autogenerated/+iDynTree/checkDoublesAreEqual.m @@ -1,3 +1,3 @@ function varargout = checkDoublesAreEqual(varargin) - [varargout{1:nargout}] = iDynTreeMEX(131, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(206, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/computeBoundingBoxFromShape.m b/bindings/matlab/autogenerated/+iDynTree/computeBoundingBoxFromShape.m index 850e7959f3..dd6655802a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/computeBoundingBoxFromShape.m +++ b/bindings/matlab/autogenerated/+iDynTree/computeBoundingBoxFromShape.m @@ -1,3 +1,3 @@ function varargout = computeBoundingBoxFromShape(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1767, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1850, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/computeBoxVertices.m b/bindings/matlab/autogenerated/+iDynTree/computeBoxVertices.m index 8d173a7ade..4885478ebf 100644 --- a/bindings/matlab/autogenerated/+iDynTree/computeBoxVertices.m +++ b/bindings/matlab/autogenerated/+iDynTree/computeBoxVertices.m @@ -1,3 +1,3 @@ function varargout = computeBoxVertices(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1768, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1851, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/computeLinkNetWrenchesWithoutGravity.m b/bindings/matlab/autogenerated/+iDynTree/computeLinkNetWrenchesWithoutGravity.m index 965ee889df..d9602d58bf 100644 --- a/bindings/matlab/autogenerated/+iDynTree/computeLinkNetWrenchesWithoutGravity.m +++ b/bindings/matlab/autogenerated/+iDynTree/computeLinkNetWrenchesWithoutGravity.m @@ -1,3 +1,3 @@ function varargout = computeLinkNetWrenchesWithoutGravity(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1531, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1612, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/computeTransformToSubModelBase.m b/bindings/matlab/autogenerated/+iDynTree/computeTransformToSubModelBase.m index 71633fec57..d74a786731 100644 --- a/bindings/matlab/autogenerated/+iDynTree/computeTransformToSubModelBase.m +++ b/bindings/matlab/autogenerated/+iDynTree/computeTransformToSubModelBase.m @@ -1,3 +1,3 @@ function varargout = computeTransformToSubModelBase(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1179, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1310, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/computeTransformToTraversalBase.m b/bindings/matlab/autogenerated/+iDynTree/computeTransformToTraversalBase.m index a9e89b78eb..231f179215 100644 --- a/bindings/matlab/autogenerated/+iDynTree/computeTransformToTraversalBase.m +++ b/bindings/matlab/autogenerated/+iDynTree/computeTransformToTraversalBase.m @@ -1,3 +1,3 @@ function varargout = computeTransformToTraversalBase(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1178, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1309, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/createModelWithNormalizedJointNumbering.m b/bindings/matlab/autogenerated/+iDynTree/createModelWithNormalizedJointNumbering.m index 45496d4cfe..94f5cc3054 100644 --- a/bindings/matlab/autogenerated/+iDynTree/createModelWithNormalizedJointNumbering.m +++ b/bindings/matlab/autogenerated/+iDynTree/createModelWithNormalizedJointNumbering.m @@ -1,3 +1,3 @@ function varargout = createModelWithNormalizedJointNumbering(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1167, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1298, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/createReducedModel.m b/bindings/matlab/autogenerated/+iDynTree/createReducedModel.m index ab48d4f9f7..07045134f2 100644 --- a/bindings/matlab/autogenerated/+iDynTree/createReducedModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/createReducedModel.m @@ -1,3 +1,3 @@ function varargout = createReducedModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1166, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1297, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDF.m b/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDF.m index ea6e295631..de19cfcfa1 100644 --- a/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDF.m +++ b/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDF.m @@ -1,3 +1,3 @@ function varargout = dofsListFromURDF(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1441, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1520, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDFString.m b/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDFString.m index 6f28ddf86f..acc09a64ed 100644 --- a/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDFString.m +++ b/bindings/matlab/autogenerated/+iDynTree/dofsListFromURDFString.m @@ -1,3 +1,3 @@ function varargout = dofsListFromURDFString(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1442, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1521, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/dynamic_extent.m b/bindings/matlab/autogenerated/+iDynTree/dynamic_extent.m index 3a88f3dde3..52e6c00051 100644 --- a/bindings/matlab/autogenerated/+iDynTree/dynamic_extent.m +++ b/bindings/matlab/autogenerated/+iDynTree/dynamic_extent.m @@ -1,3 +1,3 @@ function v = dynamic_extent() - v = iDynTreeMEX(697); + v = iDynTreeMEX(746); end diff --git a/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelAccKinematics.m b/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelAccKinematics.m index 2ca44a6caa..104eb136a4 100644 --- a/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelAccKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelAccKinematics.m @@ -1,3 +1,3 @@ function varargout = dynamicsEstimationForwardVelAccKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1529, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1610, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelKinematics.m b/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelKinematics.m index 04f4368c73..55ca84501e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelKinematics.m +++ b/bindings/matlab/autogenerated/+iDynTree/dynamicsEstimationForwardVelKinematics.m @@ -1,3 +1,3 @@ function varargout = dynamicsEstimationForwardVelKinematics(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1530, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1611, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenches.m b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenches.m index 178cd01fe5..e32a184ad5 100644 --- a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenches.m +++ b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenches.m @@ -1,3 +1,3 @@ function varargout = estimateExternalWrenches(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1528, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1609, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesBuffers.m b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesBuffers.m index ac4ae22441..55d8319f25 100644 --- a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesBuffers.m +++ b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesBuffers.m @@ -9,76 +9,76 @@ self.swigPtr = varargin{1}.swigPtr; end else - tmp = iDynTreeMEX(1511, varargin{:}); + tmp = iDynTreeMEX(1592, varargin{:}); self.swigPtr = tmp.swigPtr; tmp.SwigClear(); end end function varargout = resize(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1512, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1593, self, varargin{:}); end function varargout = getNrOfSubModels(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1513, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1594, self, varargin{:}); end function varargout = getNrOfLinks(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1514, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1595, self, varargin{:}); end function varargout = isConsistent(self,varargin) - [varargout{1:nargout}] = iDynTreeMEX(1515, self, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1596, self, varargin{:}); end function varargout = A(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1516, self); + varargout{1} = iDynTreeMEX(1597, self); else nargoutchk(0, 0) - iDynTreeMEX(1517, self, varargin{1}); + iDynTreeMEX(1598, self, varargin{1}); end end function varargout = x(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1518, self); + varargout{1} = iDynTreeMEX(1599, self); else nargoutchk(0, 0) - iDynTreeMEX(1519, self, varargin{1}); + iDynTreeMEX(1600, self, varargin{1}); end end function varargout = b(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1520, self); + varargout{1} = iDynTreeMEX(1601, self); else nargoutchk(0, 0) - iDynTreeMEX(1521, self, varargin{1}); + iDynTreeMEX(1602, self, varargin{1}); end end function varargout = b_contacts_subtree(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1522, self); + varargout{1} = iDynTreeMEX(1603, self); else nargoutchk(0, 0) - iDynTreeMEX(1523, self, varargin{1}); + iDynTreeMEX(1604, self, varargin{1}); end end function varargout = subModelBase_H_link(self, varargin) narginchk(1, 2) if nargin==1 nargoutchk(0, 1) - varargout{1} = iDynTreeMEX(1524, self); + varargout{1} = iDynTreeMEX(1605, self); else nargoutchk(0, 0) - iDynTreeMEX(1525, self, varargin{1}); + iDynTreeMEX(1606, self, varargin{1}); end end function delete(self) if self.swigPtr - iDynTreeMEX(1526, self); + iDynTreeMEX(1607, self); self.SwigClear(); end end diff --git a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesWithoutInternalFT.m b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesWithoutInternalFT.m index 7732b1a4ba..433d7252d9 100644 --- a/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesWithoutInternalFT.m +++ b/bindings/matlab/autogenerated/+iDynTree/estimateExternalWrenchesWithoutInternalFT.m @@ -1,3 +1,3 @@ function varargout = estimateExternalWrenchesWithoutInternalFT(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1527, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1608, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/estimateInertialParametersFromLinkBoundingBoxesAndTotalMass.m b/bindings/matlab/autogenerated/+iDynTree/estimateInertialParametersFromLinkBoundingBoxesAndTotalMass.m index 04dca54ff5..52c64c12ea 100644 --- a/bindings/matlab/autogenerated/+iDynTree/estimateInertialParametersFromLinkBoundingBoxesAndTotalMass.m +++ b/bindings/matlab/autogenerated/+iDynTree/estimateInertialParametersFromLinkBoundingBoxesAndTotalMass.m @@ -1,3 +1,3 @@ function varargout = estimateInertialParametersFromLinkBoundingBoxesAndTotalMass(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1766, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1849, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/estimateLinkContactWrenchesFromLinkNetExternalWrenches.m b/bindings/matlab/autogenerated/+iDynTree/estimateLinkContactWrenchesFromLinkNetExternalWrenches.m index 3eff90209c..33e274013e 100644 --- a/bindings/matlab/autogenerated/+iDynTree/estimateLinkContactWrenchesFromLinkNetExternalWrenches.m +++ b/bindings/matlab/autogenerated/+iDynTree/estimateLinkContactWrenchesFromLinkNetExternalWrenches.m @@ -1,3 +1,3 @@ function varargout = estimateLinkContactWrenchesFromLinkNetExternalWrenches(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1532, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1613, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/extractSubModel.m b/bindings/matlab/autogenerated/+iDynTree/extractSubModel.m index 7c92bc5a6e..c524f4ecba 100644 --- a/bindings/matlab/autogenerated/+iDynTree/extractSubModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/extractSubModel.m @@ -1,3 +1,3 @@ function varargout = extractSubModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1168, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1299, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomChain.m b/bindings/matlab/autogenerated/+iDynTree/getRandomChain.m index 00b0194950..1491e37659 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomChain.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomChain.m @@ -1,3 +1,3 @@ function varargout = getRandomChain(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1162, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1293, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomInverseDynamicsInputs.m b/bindings/matlab/autogenerated/+iDynTree/getRandomInverseDynamicsInputs.m index 4d4eef1a7b..af8d1a6759 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomInverseDynamicsInputs.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomInverseDynamicsInputs.m @@ -1,3 +1,3 @@ function varargout = getRandomInverseDynamicsInputs(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1164, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1295, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomJointPositions.m b/bindings/matlab/autogenerated/+iDynTree/getRandomJointPositions.m index 9656cec88e..847eb79405 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomJointPositions.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomJointPositions.m @@ -1,3 +1,3 @@ function varargout = getRandomJointPositions(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1163, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1294, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomLink.m b/bindings/matlab/autogenerated/+iDynTree/getRandomLink.m index 41c44c7ab7..0353ae4f15 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomLink.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomLink.m @@ -1,3 +1,3 @@ function varargout = getRandomLink(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1155, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1286, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomLinkIndexOfModel.m b/bindings/matlab/autogenerated/+iDynTree/getRandomLinkIndexOfModel.m index 61606d636a..0b654d16fd 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomLinkIndexOfModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomLinkIndexOfModel.m @@ -1,3 +1,3 @@ function varargout = getRandomLinkIndexOfModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1158, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1289, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomLinkOfModel.m b/bindings/matlab/autogenerated/+iDynTree/getRandomLinkOfModel.m index 2bfe224258..133c2459e3 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomLinkOfModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomLinkOfModel.m @@ -1,3 +1,3 @@ function varargout = getRandomLinkOfModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1159, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1290, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getRandomModel.m b/bindings/matlab/autogenerated/+iDynTree/getRandomModel.m index 9973f81675..759ef056ae 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getRandomModel.m +++ b/bindings/matlab/autogenerated/+iDynTree/getRandomModel.m @@ -1,3 +1,3 @@ function varargout = getRandomModel(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1161, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1292, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/getSensorTypeSize.m b/bindings/matlab/autogenerated/+iDynTree/getSensorTypeSize.m index cab9f35c2f..afe498a0c0 100644 --- a/bindings/matlab/autogenerated/+iDynTree/getSensorTypeSize.m +++ b/bindings/matlab/autogenerated/+iDynTree/getSensorTypeSize.m @@ -1,3 +1,3 @@ function varargout = getSensorTypeSize(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1298, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1119, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/input_dimensions.m b/bindings/matlab/autogenerated/+iDynTree/input_dimensions.m index 08623c61db..84503b73e9 100644 --- a/bindings/matlab/autogenerated/+iDynTree/input_dimensions.m +++ b/bindings/matlab/autogenerated/+iDynTree/input_dimensions.m @@ -1,3 +1,3 @@ function v = input_dimensions() - v = iDynTreeMEX(1721); + v = iDynTreeMEX(1804); end diff --git a/bindings/matlab/autogenerated/+iDynTree/int2string.m b/bindings/matlab/autogenerated/+iDynTree/int2string.m index 23c0146047..69552b7800 100644 --- a/bindings/matlab/autogenerated/+iDynTree/int2string.m +++ b/bindings/matlab/autogenerated/+iDynTree/int2string.m @@ -1,3 +1,3 @@ function varargout = int2string(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1160, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1291, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/isDOFBerdyDynamicVariable.m b/bindings/matlab/autogenerated/+iDynTree/isDOFBerdyDynamicVariable.m index 1a31658bc1..fd37a7bd77 100644 --- a/bindings/matlab/autogenerated/+iDynTree/isDOFBerdyDynamicVariable.m +++ b/bindings/matlab/autogenerated/+iDynTree/isDOFBerdyDynamicVariable.m @@ -1,3 +1,3 @@ function varargout = isDOFBerdyDynamicVariable(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1559, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1642, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/isJointBerdyDynamicVariable.m b/bindings/matlab/autogenerated/+iDynTree/isJointBerdyDynamicVariable.m index 6587cb5965..56042b787c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/isJointBerdyDynamicVariable.m +++ b/bindings/matlab/autogenerated/+iDynTree/isJointBerdyDynamicVariable.m @@ -1,3 +1,3 @@ function varargout = isJointBerdyDynamicVariable(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1558, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1641, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/isJointSensor.m b/bindings/matlab/autogenerated/+iDynTree/isJointSensor.m index 8cbf36125d..6ad7d6c03f 100644 --- a/bindings/matlab/autogenerated/+iDynTree/isJointSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/isJointSensor.m @@ -1,3 +1,3 @@ function varargout = isJointSensor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1297, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1118, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/isLinkBerdyDynamicVariable.m b/bindings/matlab/autogenerated/+iDynTree/isLinkBerdyDynamicVariable.m index 579913b79a..0e187edf37 100644 --- a/bindings/matlab/autogenerated/+iDynTree/isLinkBerdyDynamicVariable.m +++ b/bindings/matlab/autogenerated/+iDynTree/isLinkBerdyDynamicVariable.m @@ -1,3 +1,3 @@ function varargout = isLinkBerdyDynamicVariable(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1557, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1640, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/isLinkSensor.m b/bindings/matlab/autogenerated/+iDynTree/isLinkSensor.m index fe4dc0783f..a811fd8450 100644 --- a/bindings/matlab/autogenerated/+iDynTree/isLinkSensor.m +++ b/bindings/matlab/autogenerated/+iDynTree/isLinkSensor.m @@ -1,3 +1,3 @@ function varargout = isLinkSensor(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1296, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1117, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/output_dimensions_with_magnetometer.m b/bindings/matlab/autogenerated/+iDynTree/output_dimensions_with_magnetometer.m index 23f09b4984..e08c71b12a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/output_dimensions_with_magnetometer.m +++ b/bindings/matlab/autogenerated/+iDynTree/output_dimensions_with_magnetometer.m @@ -1,3 +1,3 @@ function v = output_dimensions_with_magnetometer() - v = iDynTreeMEX(1719); + v = iDynTreeMEX(1802); end diff --git a/bindings/matlab/autogenerated/+iDynTree/output_dimensions_without_magnetometer.m b/bindings/matlab/autogenerated/+iDynTree/output_dimensions_without_magnetometer.m index c184162b46..d9ca9c0b7a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/output_dimensions_without_magnetometer.m +++ b/bindings/matlab/autogenerated/+iDynTree/output_dimensions_without_magnetometer.m @@ -1,3 +1,3 @@ function v = output_dimensions_without_magnetometer() - v = iDynTreeMEX(1720); + v = iDynTreeMEX(1803); end diff --git a/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurements.m b/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurements.m index df7444d008..57c1cb3902 100644 --- a/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurements.m +++ b/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurements.m @@ -1,3 +1,3 @@ function varargout = predictSensorsMeasurements(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1439, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1403, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurementsFromRawBuffers.m b/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurementsFromRawBuffers.m index 1f8280d5b6..144b9ab7c9 100644 --- a/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurementsFromRawBuffers.m +++ b/bindings/matlab/autogenerated/+iDynTree/predictSensorsMeasurementsFromRawBuffers.m @@ -1,3 +1,3 @@ function varargout = predictSensorsMeasurementsFromRawBuffers(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1440, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1404, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/removeFakeLinks.m b/bindings/matlab/autogenerated/+iDynTree/removeFakeLinks.m index 2bd86e5e26..250790d775 100644 --- a/bindings/matlab/autogenerated/+iDynTree/removeFakeLinks.m +++ b/bindings/matlab/autogenerated/+iDynTree/removeFakeLinks.m @@ -1,3 +1,3 @@ function varargout = removeFakeLinks(varargin) - [varargout{1:nargout}] = iDynTreeMEX(1165, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(1296, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/reportDebug.m b/bindings/matlab/autogenerated/+iDynTree/reportDebug.m index f4e360951e..75e01a0e07 100644 --- a/bindings/matlab/autogenerated/+iDynTree/reportDebug.m +++ b/bindings/matlab/autogenerated/+iDynTree/reportDebug.m @@ -1,3 +1,3 @@ function varargout = reportDebug(varargin) - [varargout{1:nargout}] = iDynTreeMEX(122, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(197, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/reportInfo.m b/bindings/matlab/autogenerated/+iDynTree/reportInfo.m index de70ac289a..92b1f0f54c 100644 --- a/bindings/matlab/autogenerated/+iDynTree/reportInfo.m +++ b/bindings/matlab/autogenerated/+iDynTree/reportInfo.m @@ -1,3 +1,3 @@ function varargout = reportInfo(varargin) - [varargout{1:nargout}] = iDynTreeMEX(121, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(196, varargin{:}); end diff --git a/bindings/matlab/autogenerated/+iDynTree/sizeOfRotationParametrization.m b/bindings/matlab/autogenerated/+iDynTree/sizeOfRotationParametrization.m index 4e922ca529..b5b0ef676a 100644 --- a/bindings/matlab/autogenerated/+iDynTree/sizeOfRotationParametrization.m +++ b/bindings/matlab/autogenerated/+iDynTree/sizeOfRotationParametrization.m @@ -1,3 +1,3 @@ function varargout = sizeOfRotationParametrization(varargin) - [varargout{1:nargout}] = iDynTreeMEX(2052, varargin{:}); + [varargout{1:nargout}] = iDynTreeMEX(2135, varargin{:}); end diff --git a/bindings/matlab/autogenerated/iDynTreeMATLAB_wrap.cxx b/bindings/matlab/autogenerated/iDynTreeMATLAB_wrap.cxx index c2a81ebbcc..1fd57edf5d 100644 --- a/bindings/matlab/autogenerated/iDynTreeMATLAB_wrap.cxx +++ b/bindings/matlab/autogenerated/iDynTreeMATLAB_wrap.cxx @@ -1323,72 +1323,72 @@ namespace swig { #define SWIGTYPE_p_iDynTree__Polygon swig_types[111] #define SWIGTYPE_p_iDynTree__Polygon2D swig_types[112] #define SWIGTYPE_p_iDynTree__Position swig_types[113] -#define SWIGTYPE_p_iDynTree__PositionRaw swig_types[114] -#define SWIGTYPE_p_iDynTree__PrismaticJoint swig_types[115] -#define SWIGTYPE_p_iDynTree__RevoluteJoint swig_types[116] -#define SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization swig_types[117] -#define SWIGTYPE_p_iDynTree__Rotation swig_types[118] -#define SWIGTYPE_p_iDynTree__RotationRaw swig_types[119] -#define SWIGTYPE_p_iDynTree__RotationalInertiaRaw swig_types[120] -#define SWIGTYPE_p_iDynTree__Sensor swig_types[121] -#define SWIGTYPE_p_iDynTree__SensorsList swig_types[122] -#define SWIGTYPE_p_iDynTree__SensorsMeasurements swig_types[123] -#define SWIGTYPE_p_iDynTree__SimpleLeggedOdometry swig_types[124] -#define SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor swig_types[125] -#define SWIGTYPE_p_iDynTree__SolidShape swig_types[126] -#define SWIGTYPE_p_iDynTree__SpanT_double__1_t swig_types[127] -#define SWIGTYPE_p_iDynTree__SpanT_double_const__1_t swig_types[128] -#define SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t swig_types[129] -#define SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t swig_types[130] -#define SWIGTYPE_p_iDynTree__SpatialAcc swig_types[131] -#define SWIGTYPE_p_iDynTree__SpatialForceVector swig_types[132] -#define SWIGTYPE_p_iDynTree__SpatialInertia swig_types[133] -#define SWIGTYPE_p_iDynTree__SpatialInertiaRaw swig_types[134] -#define SWIGTYPE_p_iDynTree__SpatialMomentum swig_types[135] -#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type swig_types[136] -#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type swig_types[137] -#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type swig_types[138] -#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type swig_types[139] -#define SWIGTYPE_p_iDynTree__SpatialMotionVector swig_types[140] -#define SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t swig_types[141] -#define SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t swig_types[142] -#define SWIGTYPE_p_iDynTree__Sphere swig_types[143] -#define SWIGTYPE_p_iDynTree__SubModelDecomposition swig_types[144] -#define SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor swig_types[145] -#define SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor swig_types[146] -#define SWIGTYPE_p_iDynTree__Transform swig_types[147] -#define SWIGTYPE_p_iDynTree__TransformDerivative swig_types[148] -#define SWIGTYPE_p_iDynTree__Traversal swig_types[149] -#define SWIGTYPE_p_iDynTree__Triplets swig_types[150] -#define SWIGTYPE_p_iDynTree__Twist swig_types[151] -#define SWIGTYPE_p_iDynTree__UnknownWrenchContact swig_types[152] -#define SWIGTYPE_p_iDynTree__VectorDynSize swig_types[153] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t swig_types[154] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t swig_types[155] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_2_t swig_types[156] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t swig_types[157] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t swig_types[158] -#define SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t swig_types[159] -#define SWIGTYPE_p_iDynTree__Visualizer swig_types[160] -#define SWIGTYPE_p_iDynTree__VisualizerOptions swig_types[161] -#define SWIGTYPE_p_iDynTree__Wrench swig_types[162] -#define SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t swig_types[163] -#define SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t swig_types[164] -#define SWIGTYPE_p_iDynTree__estimateExternalWrenchesBuffers swig_types[165] -#define SWIGTYPE_p_index_type swig_types[166] -#define SWIGTYPE_p_iterator swig_types[167] -#define SWIGTYPE_p_pointer swig_types[168] -#define SWIGTYPE_p_reference swig_types[169] -#define SWIGTYPE_p_reverse_iterator swig_types[170] -#define SWIGTYPE_p_size_type swig_types[171] -#define SWIGTYPE_p_std__allocatorT_iDynTree__BerdyDynamicVariable_t swig_types[172] -#define SWIGTYPE_p_std__allocatorT_iDynTree__BerdySensor_t swig_types[173] -#define SWIGTYPE_p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t swig_types[174] -#define SWIGTYPE_p_std__allocatorT_iDynTree__SolidShape_p_t swig_types[175] +#define SWIGTYPE_p_iDynTree__PrismaticJoint swig_types[114] +#define SWIGTYPE_p_iDynTree__RevoluteJoint swig_types[115] +#define SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization swig_types[116] +#define SWIGTYPE_p_iDynTree__Rotation swig_types[117] +#define SWIGTYPE_p_iDynTree__RotationalInertia swig_types[118] +#define SWIGTYPE_p_iDynTree__Sensor swig_types[119] +#define SWIGTYPE_p_iDynTree__SensorsList swig_types[120] +#define SWIGTYPE_p_iDynTree__SensorsMeasurements swig_types[121] +#define SWIGTYPE_p_iDynTree__SimpleLeggedOdometry swig_types[122] +#define SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor swig_types[123] +#define SWIGTYPE_p_iDynTree__SolidShape swig_types[124] +#define SWIGTYPE_p_iDynTree__SpanT_double__1_t swig_types[125] +#define SWIGTYPE_p_iDynTree__SpanT_double_const__1_t swig_types[126] +#define SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t swig_types[127] +#define SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t swig_types[128] +#define SWIGTYPE_p_iDynTree__SpatialAcc swig_types[129] +#define SWIGTYPE_p_iDynTree__SpatialForceVector swig_types[130] +#define SWIGTYPE_p_iDynTree__SpatialInertia swig_types[131] +#define SWIGTYPE_p_iDynTree__SpatialMomentum swig_types[132] +#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type swig_types[133] +#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type swig_types[134] +#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type swig_types[135] +#define SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type swig_types[136] +#define SWIGTYPE_p_iDynTree__SpatialMotionVector swig_types[137] +#define SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t swig_types[138] +#define SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t swig_types[139] +#define SWIGTYPE_p_iDynTree__Sphere swig_types[140] +#define SWIGTYPE_p_iDynTree__SubModelDecomposition swig_types[141] +#define SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor swig_types[142] +#define SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor swig_types[143] +#define SWIGTYPE_p_iDynTree__Transform swig_types[144] +#define SWIGTYPE_p_iDynTree__TransformDerivative swig_types[145] +#define SWIGTYPE_p_iDynTree__Traversal swig_types[146] +#define SWIGTYPE_p_iDynTree__Triplets swig_types[147] +#define SWIGTYPE_p_iDynTree__Twist swig_types[148] +#define SWIGTYPE_p_iDynTree__UnknownWrenchContact swig_types[149] +#define SWIGTYPE_p_iDynTree__VectorDynSize swig_types[150] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t swig_types[151] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t swig_types[152] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_2_t swig_types[153] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t swig_types[154] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t swig_types[155] +#define SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t swig_types[156] +#define SWIGTYPE_p_iDynTree__Visualizer swig_types[157] +#define SWIGTYPE_p_iDynTree__VisualizerOptions swig_types[158] +#define SWIGTYPE_p_iDynTree__Wrench swig_types[159] +#define SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t swig_types[160] +#define SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t swig_types[161] +#define SWIGTYPE_p_iDynTree__estimateExternalWrenchesBuffers swig_types[162] +#define SWIGTYPE_p_index_type swig_types[163] +#define SWIGTYPE_p_iterator swig_types[164] +#define SWIGTYPE_p_pointer swig_types[165] +#define SWIGTYPE_p_ptrdiff_t swig_types[166] +#define SWIGTYPE_p_reference swig_types[167] +#define SWIGTYPE_p_reverse_iterator swig_types[168] +#define SWIGTYPE_p_size_type swig_types[169] +#define SWIGTYPE_p_std__allocatorT_iDynTree__BerdyDynamicVariable_t swig_types[170] +#define SWIGTYPE_p_std__allocatorT_iDynTree__BerdySensor_t swig_types[171] +#define SWIGTYPE_p_std__allocatorT_iDynTree__MatrixDynSize_t swig_types[172] +#define SWIGTYPE_p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t swig_types[173] +#define SWIGTYPE_p_std__allocatorT_iDynTree__SolidShape_p_t swig_types[174] +#define SWIGTYPE_p_std__allocatorT_iDynTree__VectorDynSize_t swig_types[175] #define SWIGTYPE_p_std__allocatorT_int_t swig_types[176] -#define SWIGTYPE_p_std__allocatorT_std__string_t swig_types[177] -#define SWIGTYPE_p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t swig_types[178] -#define SWIGTYPE_p_std__ptrdiff_t swig_types[179] +#define SWIGTYPE_p_std__allocatorT_std__ptrdiff_t_t swig_types[177] +#define SWIGTYPE_p_std__allocatorT_std__string_t swig_types[178] +#define SWIGTYPE_p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t swig_types[179] #define SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t swig_types[180] #define SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t swig_types[181] #define SWIGTYPE_p_std__size_t swig_types[182] @@ -2972,6 +2972,7 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st /* Note : always include headers following the inheritance order */ #include +#include //Utils #include "iDynTree/Utils.h" @@ -2985,7 +2986,6 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st #include "iDynTree/VectorFixSize.h" // Basic Vectors: Point Vectors and Spatial Vectors -#include "iDynTree/PositionRaw.h" #include "iDynTree/Position.h" #include "iDynTree/SpatialForceVector.h" #include "iDynTree/SpatialMotionVector.h" @@ -2998,14 +2998,13 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st #include "iDynTree/Axis.h" // Inertias -#include "iDynTree/RotationalInertiaRaw.h" -#include "iDynTree/SpatialInertiaRaw.h" +#include "iDynTree/RotationalInertia.h" +#include "iDynTree/SpatialInertia.h" #include "iDynTree/SpatialInertia.h" #include "iDynTree/ArticulatedBodyInertia.h" #include "iDynTree/InertiaNonLinearParametrization.h" // Transformations: Rotation and Transform -#include "iDynTree/RotationRaw.h" #include "iDynTree/Rotation.h" #include "iDynTree/Transform.h" #include "iDynTree/TransformDerivative.h" @@ -3022,6 +3021,7 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st #include "iDynTree/PrismaticJoint.h" #include "iDynTree/Traversal.h" #include "iDynTree/SolidShapes.h" +#include "iDynTree/Sensors.h" #include "iDynTree/Model.h" #include "iDynTree/JointState.h" #include "iDynTree/FreeFloatingMatrices.h" @@ -3030,14 +3030,6 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st #include "iDynTree/ModelTestUtils.h" #include "iDynTree/ModelTransformers.h" #include "iDynTree/SubModel.h" - -// Kinematics & Dynamics related functions -#include "iDynTree/ForwardKinematics.h" -#include "iDynTree/Dynamics.h" -#include "iDynTree/DenavitHartenberg.h" - -// Sensors related data structures -#include "iDynTree/Sensors.h" #include "iDynTree/SixAxisForceTorqueSensor.h" #include "iDynTree/AccelerometerSensor.h" #include "iDynTree/GyroscopeSensor.h" @@ -3045,6 +3037,11 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st #include "iDynTree/ThreeAxisForceTorqueContactSensor.h" #include "iDynTree/PredictSensorsMeasurements.h" +// Kinematics & Dynamics related functions +#include "iDynTree/ForwardKinematics.h" +#include "iDynTree/Dynamics.h" +#include "iDynTree/DenavitHartenberg.h" + // Model loading from external formats #include "iDynTree/URDFDofsImport.h" #include "iDynTree/ModelLoader.h" @@ -3078,6 +3075,120 @@ SWIGINTERN void std_vector_Sl_int_Sg__insert__SWIG_1(std::vector< int > *self,st + namespace swig { + template <> struct traits< iDynTree::MatrixDynSize > { + typedef pointer_category category; + static const char* type_name() { return"iDynTree::MatrixDynSize"; } + }; + } + + + namespace swig { + template <> struct traits > > { + typedef pointer_category category; + static const char* type_name() { + return "std::vector<" "iDynTree::MatrixDynSize" "," "std::allocator< iDynTree::MatrixDynSize >" " >"; + } + }; + } + +SWIGINTERN std::vector< iDynTree::MatrixDynSize >::value_type std_vector_Sl_iDynTree_MatrixDynSize_Sg__pop(std::vector< iDynTree::MatrixDynSize > *self){ + if (self->size() == 0) + throw std::out_of_range("pop from empty container"); + std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >::value_type x = self->back(); + self->pop_back(); + return x; + } +SWIGINTERN std::vector< iDynTree::MatrixDynSize >::value_type std_vector_Sl_iDynTree_MatrixDynSize_Sg__brace(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::difference_type i){ + return *(swig::cgetpos(self, i)); + } +SWIGINTERN void std_vector_Sl_iDynTree_MatrixDynSize_Sg__setbrace(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::value_type x,std::vector< iDynTree::MatrixDynSize >::difference_type i){ + *(swig::getpos(self,i)) = x; + } +SWIGINTERN void std_vector_Sl_iDynTree_MatrixDynSize_Sg__append(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::value_type x){ + self->push_back(x); + } +SWIGINTERN std::vector< iDynTree::MatrixDynSize >::iterator std_vector_Sl_iDynTree_MatrixDynSize_Sg__erase__SWIG_0(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::iterator pos){ return self->erase(pos); } +SWIGINTERN std::vector< iDynTree::MatrixDynSize >::iterator std_vector_Sl_iDynTree_MatrixDynSize_Sg__erase__SWIG_1(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::iterator first,std::vector< iDynTree::MatrixDynSize >::iterator last){ return self->erase(first, last); } +SWIGINTERN std::vector< iDynTree::MatrixDynSize >::iterator std_vector_Sl_iDynTree_MatrixDynSize_Sg__insert__SWIG_0(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::iterator pos,std::vector< iDynTree::MatrixDynSize >::value_type const &x){ return self->insert(pos, x); } +SWIGINTERN void std_vector_Sl_iDynTree_MatrixDynSize_Sg__insert__SWIG_1(std::vector< iDynTree::MatrixDynSize > *self,std::vector< iDynTree::MatrixDynSize >::iterator pos,std::vector< iDynTree::MatrixDynSize >::size_type n,std::vector< iDynTree::MatrixDynSize >::value_type const &x){ self->insert(pos, n, x); } + + namespace swig { + template <> struct traits< iDynTree::VectorDynSize > { + typedef pointer_category category; + static const char* type_name() { return"iDynTree::VectorDynSize"; } + }; + } + + + namespace swig { + template <> struct traits > > { + typedef pointer_category category; + static const char* type_name() { + return "std::vector<" "iDynTree::VectorDynSize" "," "std::allocator< iDynTree::VectorDynSize >" " >"; + } + }; + } + +SWIGINTERN std::vector< iDynTree::VectorDynSize >::value_type std_vector_Sl_iDynTree_VectorDynSize_Sg__pop(std::vector< iDynTree::VectorDynSize > *self){ + if (self->size() == 0) + throw std::out_of_range("pop from empty container"); + std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >::value_type x = self->back(); + self->pop_back(); + return x; + } +SWIGINTERN std::vector< iDynTree::VectorDynSize >::value_type std_vector_Sl_iDynTree_VectorDynSize_Sg__brace(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::difference_type i){ + return *(swig::cgetpos(self, i)); + } +SWIGINTERN void std_vector_Sl_iDynTree_VectorDynSize_Sg__setbrace(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::value_type x,std::vector< iDynTree::VectorDynSize >::difference_type i){ + *(swig::getpos(self,i)) = x; + } +SWIGINTERN void std_vector_Sl_iDynTree_VectorDynSize_Sg__append(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::value_type x){ + self->push_back(x); + } +SWIGINTERN std::vector< iDynTree::VectorDynSize >::iterator std_vector_Sl_iDynTree_VectorDynSize_Sg__erase__SWIG_0(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::iterator pos){ return self->erase(pos); } +SWIGINTERN std::vector< iDynTree::VectorDynSize >::iterator std_vector_Sl_iDynTree_VectorDynSize_Sg__erase__SWIG_1(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::iterator first,std::vector< iDynTree::VectorDynSize >::iterator last){ return self->erase(first, last); } +SWIGINTERN std::vector< iDynTree::VectorDynSize >::iterator std_vector_Sl_iDynTree_VectorDynSize_Sg__insert__SWIG_0(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::iterator pos,std::vector< iDynTree::VectorDynSize >::value_type const &x){ return self->insert(pos, x); } +SWIGINTERN void std_vector_Sl_iDynTree_VectorDynSize_Sg__insert__SWIG_1(std::vector< iDynTree::VectorDynSize > *self,std::vector< iDynTree::VectorDynSize >::iterator pos,std::vector< iDynTree::VectorDynSize >::size_type n,std::vector< iDynTree::VectorDynSize >::value_type const &x){ self->insert(pos, n, x); } + + namespace swig { + template <> struct traits< ::ptrdiff_t > { + typedef pointer_category category; + static const char* type_name() { return"::ptrdiff_t"; } + }; + } + + + namespace swig { + template <> struct traits > > { + typedef pointer_category category; + static const char* type_name() { + return "std::vector<" "::ptrdiff_t" "," "std::allocator< ::ptrdiff_t >" " >"; + } + }; + } + +SWIGINTERN std::vector< ::ptrdiff_t >::value_type std_vector_Sl_std_ptrdiff_t_Sg__pop(std::vector< std::ptrdiff_t > *self){ + if (self->size() == 0) + throw std::out_of_range("pop from empty container"); + std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >::value_type x = self->back(); + self->pop_back(); + return x; + } +SWIGINTERN std::vector< ::ptrdiff_t >::value_type std_vector_Sl_std_ptrdiff_t_Sg__brace(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::difference_type i){ + return *(swig::cgetpos(self, i)); + } +SWIGINTERN void std_vector_Sl_std_ptrdiff_t_Sg__setbrace(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::value_type x,std::vector< ::ptrdiff_t >::difference_type i){ + *(swig::getpos(self,i)) = x; + } +SWIGINTERN void std_vector_Sl_std_ptrdiff_t_Sg__append(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::value_type x){ + self->push_back(x); + } +SWIGINTERN std::vector< ::ptrdiff_t >::iterator std_vector_Sl_std_ptrdiff_t_Sg__erase__SWIG_0(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::iterator pos){ return self->erase(pos); } +SWIGINTERN std::vector< ::ptrdiff_t >::iterator std_vector_Sl_std_ptrdiff_t_Sg__erase__SWIG_1(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::iterator first,std::vector< ::ptrdiff_t >::iterator last){ return self->erase(first, last); } +SWIGINTERN std::vector< ::ptrdiff_t >::iterator std_vector_Sl_std_ptrdiff_t_Sg__insert__SWIG_0(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::iterator pos,std::vector< ::ptrdiff_t >::value_type const &x){ return self->insert(pos, x); } +SWIGINTERN void std_vector_Sl_std_ptrdiff_t_Sg__insert__SWIG_1(std::vector< std::ptrdiff_t > *self,std::vector< ::ptrdiff_t >::iterator pos,std::vector< ::ptrdiff_t >::size_type n,std::vector< ::ptrdiff_t >::value_type const &x){ self->insert(pos, n, x); } + namespace swig { template <> struct traits< iDynTree::BerdySensor > { typedef pointer_category category; @@ -4379,6 +4490,31 @@ SWIGINTERN iDynTree::PrismaticJoint *iDynTree_IJoint_asPrismaticJoint(iDynTree:: static_cast(self); return p; } +SWIGINTERN iDynTree::SixAxisForceTorqueSensor *iDynTree_SensorsList_getSixAxisForceTorqueSensor(iDynTree::SensorsList const *self,int sensor_index){ + iDynTree::SixAxisForceTorqueSensor* p = + static_cast(self->getSensor(iDynTree::SIX_AXIS_FORCE_TORQUE,sensor_index)); + return p; + } +SWIGINTERN iDynTree::AccelerometerSensor *iDynTree_SensorsList_getAccelerometerSensor(iDynTree::SensorsList const *self,int sensor_index){ + iDynTree::AccelerometerSensor* p = + static_cast(self->getSensor(iDynTree::ACCELEROMETER,sensor_index)); + return p; + } +SWIGINTERN iDynTree::GyroscopeSensor *iDynTree_SensorsList_getGyroscopeSensor(iDynTree::SensorsList const *self,int sensor_index){ + iDynTree::GyroscopeSensor* p = + static_cast(self->getSensor(iDynTree::GYROSCOPE,sensor_index)); + return p; + } +SWIGINTERN iDynTree::ThreeAxisAngularAccelerometerSensor *iDynTree_SensorsList_getThreeAxisAngularAccelerometerSensor(iDynTree::SensorsList const *self,int sensor_index){ + iDynTree::ThreeAxisAngularAccelerometerSensor* p = + static_cast(self->getSensor(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER,sensor_index)); + return p; + } +SWIGINTERN iDynTree::ThreeAxisForceTorqueContactSensor *iDynTree_SensorsList_getThreeAxisForceTorqueContactSensor(iDynTree::SensorsList const *self,int sensor_index){ + iDynTree::ThreeAxisForceTorqueContactSensor* p = + static_cast(self->getSensor(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT,sensor_index)); + return p; + } namespace swig { template <> struct traits< iDynTree::SolidShape > { @@ -4447,31 +4583,6 @@ SWIGINTERN std::vector< std::vector< iDynTree::SolidShape * > >::iterator std_ve SWIGINTERN std::vector< std::vector< iDynTree::SolidShape * > >::iterator std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__erase__SWIG_1(std::vector< std::vector< iDynTree::SolidShape * > > *self,std::vector< std::vector< iDynTree::SolidShape * > >::iterator first,std::vector< std::vector< iDynTree::SolidShape * > >::iterator last){ return self->erase(first, last); } SWIGINTERN std::vector< std::vector< iDynTree::SolidShape * > >::iterator std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_0(std::vector< std::vector< iDynTree::SolidShape * > > *self,std::vector< std::vector< iDynTree::SolidShape * > >::iterator pos,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &x){ return self->insert(pos, x); } SWIGINTERN void std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_1(std::vector< std::vector< iDynTree::SolidShape * > > *self,std::vector< std::vector< iDynTree::SolidShape * > >::iterator pos,std::vector< std::vector< iDynTree::SolidShape * > >::size_type n,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &x){ self->insert(pos, n, x); } -SWIGINTERN iDynTree::SixAxisForceTorqueSensor *iDynTree_SensorsList_getSixAxisForceTorqueSensor(iDynTree::SensorsList const *self,int sensor_index){ - iDynTree::SixAxisForceTorqueSensor* p = - static_cast(self->getSensor(iDynTree::SIX_AXIS_FORCE_TORQUE,sensor_index)); - return p; - } -SWIGINTERN iDynTree::AccelerometerSensor *iDynTree_SensorsList_getAccelerometerSensor(iDynTree::SensorsList const *self,int sensor_index){ - iDynTree::AccelerometerSensor* p = - static_cast(self->getSensor(iDynTree::ACCELEROMETER,sensor_index)); - return p; - } -SWIGINTERN iDynTree::GyroscopeSensor *iDynTree_SensorsList_getGyroscopeSensor(iDynTree::SensorsList const *self,int sensor_index){ - iDynTree::GyroscopeSensor* p = - static_cast(self->getSensor(iDynTree::GYROSCOPE,sensor_index)); - return p; - } -SWIGINTERN iDynTree::ThreeAxisAngularAccelerometerSensor *iDynTree_SensorsList_getThreeAxisAngularAccelerometerSensor(iDynTree::SensorsList const *self,int sensor_index){ - iDynTree::ThreeAxisAngularAccelerometerSensor* p = - static_cast(self->getSensor(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER,sensor_index)); - return p; - } -SWIGINTERN iDynTree::ThreeAxisForceTorqueContactSensor *iDynTree_SensorsList_getThreeAxisForceTorqueContactSensor(iDynTree::SensorsList const *self,int sensor_index){ - iDynTree::ThreeAxisForceTorqueContactSensor* p = - static_cast(self->getSensor(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT,sensor_index)); - return p; - } namespace swig { template <> struct traits< iDynTree::MatrixFixSize< 4,4 > > { @@ -7705,29 +7816,29 @@ int _wrap_delete_IntVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_BerdySensors_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::value_type result; + std::vector< iDynTree::MatrixDynSize >::value_type result; - if (!SWIG_check_num_args("BerdySensors_pop",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_pop" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_pop" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); try { - result = std_vector_Sl_iDynTree_BerdySensor_Sg__pop(arg1); + result = std_vector_Sl_iDynTree_MatrixDynSize_Sg__pop(arg1); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::value_type(static_cast< const std::vector< iDynTree::BerdySensor >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdySensor, SWIG_POINTER_OWN | 0 ); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::MatrixDynSize >::value_type(static_cast< const std::vector< iDynTree::MatrixDynSize >::value_type& >(result))), SWIGTYPE_p_iDynTree__MatrixDynSize, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -7735,37 +7846,37 @@ int _wrap_BerdySensors_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_BerdySensors_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::difference_type arg2 ; +int _wrap_MatrixDynSizeVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::value_type result; + std::vector< iDynTree::MatrixDynSize >::value_type result; - if (!SWIG_check_num_args("BerdySensors_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_brace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_brace" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_brace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSizeVector_brace" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::difference_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdySensor >::difference_type >(val2); + arg2 = static_cast< std::vector< iDynTree::MatrixDynSize >::difference_type >(val2); try { - result = std_vector_Sl_iDynTree_BerdySensor_Sg__brace(arg1,arg2); + result = std_vector_Sl_iDynTree_MatrixDynSize_Sg__brace(arg1,arg2); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::value_type(static_cast< const std::vector< iDynTree::BerdySensor >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdySensor, SWIG_POINTER_OWN | 0 ); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::MatrixDynSize >::value_type(static_cast< const std::vector< iDynTree::MatrixDynSize >::value_type& >(result))), SWIGTYPE_p_iDynTree__MatrixDynSize, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -7773,10 +7884,10 @@ int _wrap_BerdySensors_brace(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_BerdySensors_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::value_type arg2 ; - std::vector< iDynTree::BerdySensor >::difference_type arg3 ; +int _wrap_MatrixDynSizeVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::value_type arg2 ; + std::vector< iDynTree::MatrixDynSize >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; @@ -7785,32 +7896,32 @@ int _wrap_BerdySensors_setbrace(int resc, mxArray *resv[], int argc, mxArray *ar int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_setbrace",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); { - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSizeVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type""'"); } else { - arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2)); + arg2 = *(reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp2)); } } ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdySensors_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSizeVector_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::difference_type""'"); } - arg3 = static_cast< std::vector< iDynTree::BerdySensor >::difference_type >(val3); + arg3 = static_cast< std::vector< iDynTree::MatrixDynSize >::difference_type >(val3); try { - std_vector_Sl_iDynTree_BerdySensor_Sg__setbrace(arg1,arg2,arg3); + std_vector_Sl_iDynTree_MatrixDynSize_Sg__setbrace(arg1,arg2,arg3); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); @@ -7824,35 +7935,35 @@ int _wrap_BerdySensors_setbrace(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_BerdySensors_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::value_type arg2 ; +int _wrap_MatrixDynSizeVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::value_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_append",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_append" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_append" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); { - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSizeVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type""'"); } else { - arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2)); + arg2 = *(reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp2)); } } - std_vector_Sl_iDynTree_BerdySensor_Sg__append(arg1,arg2); + std_vector_Sl_iDynTree_MatrixDynSize_Sg__append(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -7861,16 +7972,16 @@ int _wrap_BerdySensors_append(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_BerdySensors__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_MatrixDynSizeVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::vector< iDynTree::BerdySensor > *result = 0 ; + std::vector< iDynTree::MatrixDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdySensors",argc,0,0,0)) { + if (!SWIG_check_num_args("new_MatrixDynSizeVector",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); + result = (std::vector< iDynTree::MatrixDynSize > *)new std::vector< iDynTree::MatrixDynSize >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -7878,28 +7989,28 @@ int _wrap_new_BerdySensors__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_BerdySensors__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = 0 ; +int _wrap_new_MatrixDynSizeVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = 0 ; int res1 = SWIG_OLDOBJ ; mxArray * _out; - std::vector< iDynTree::BerdySensor > *result = 0 ; + std::vector< iDynTree::MatrixDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdySensors",argc,1,1,0)) { + if (!SWIG_check_num_args("new_MatrixDynSizeVector",argc,1,1,0)) { SWIG_fail; } { - std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > > *ptr = (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > > *)0; + std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > *ptr = (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > *)0; res1 = swig::asptr(argv[0], &ptr); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const &""'"); } arg1 = ptr; } - result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >((std::vector< iDynTree::BerdySensor > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); + result = (std::vector< iDynTree::MatrixDynSize > *)new std::vector< iDynTree::MatrixDynSize >((std::vector< iDynTree::MatrixDynSize > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; if (SWIG_IsNewObj(res1)) delete arg1; return 0; @@ -7909,22 +8020,22 @@ int _wrap_new_BerdySensors__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_BerdySensors_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("BerdySensors_empty",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_empty" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_empty" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = (bool)((std::vector< iDynTree::BerdySensor > const *)arg1)->empty(); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = (bool)((std::vector< iDynTree::MatrixDynSize > const *)arg1)->empty(); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -7933,22 +8044,22 @@ int _wrap_BerdySensors_empty(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_BerdySensors_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::size_type result; + std::vector< iDynTree::MatrixDynSize >::size_type result; - if (!SWIG_check_num_args("BerdySensors_size",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_size" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_size" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->size(); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = ((std::vector< iDynTree::MatrixDynSize > const *)arg1)->size(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -7957,31 +8068,31 @@ int _wrap_BerdySensors_size(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_BerdySensors_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor > *arg2 = 0 ; +int _wrap_MatrixDynSizeVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_swap",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_swap",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_swap" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_swap" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor > &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSizeVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize > &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor > &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize > &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp2); + arg2 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp2); (arg1)->swap(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -7991,23 +8102,23 @@ int _wrap_BerdySensors_swap(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_BerdySensors_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::iterator result; + std::vector< iDynTree::MatrixDynSize >::iterator result; - if (!SWIG_check_num_args("BerdySensors_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_begin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_begin" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); result = (arg1)->begin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8016,23 +8127,23 @@ int _wrap_BerdySensors_begin(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_BerdySensors_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::iterator result; + std::vector< iDynTree::MatrixDynSize >::iterator result; - if (!SWIG_check_num_args("BerdySensors_end",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_end" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_end" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); result = (arg1)->end(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8041,23 +8152,23 @@ int _wrap_BerdySensors_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_BerdySensors_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::reverse_iterator result; + std::vector< iDynTree::MatrixDynSize >::reverse_iterator result; - if (!SWIG_check_num_args("BerdySensors_rbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); result = (arg1)->rbegin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::reverse_iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::reverse_iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8066,23 +8177,23 @@ int _wrap_BerdySensors_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_BerdySensors_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::reverse_iterator result; + std::vector< iDynTree::MatrixDynSize >::reverse_iterator result; - if (!SWIG_check_num_args("BerdySensors_rend",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_rend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_rend" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_rend" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); result = (arg1)->rend(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::reverse_iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::reverse_iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8091,20 +8202,20 @@ int _wrap_BerdySensors_rend(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_BerdySensors_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_clear",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_clear",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_clear" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_clear" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); (arg1)->clear(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -8114,23 +8225,23 @@ int _wrap_BerdySensors_clear(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_BerdySensors_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - SwigValueWrapper< std::allocator< iDynTree::BerdySensor > > result; + SwigValueWrapper< std::allocator< iDynTree::MatrixDynSize > > result; - if (!SWIG_check_num_args("BerdySensors_get_allocator",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_get_allocator",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->get_allocator(); - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::allocator_type(static_cast< const std::vector< iDynTree::BerdySensor >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__BerdySensor_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = ((std::vector< iDynTree::MatrixDynSize > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::MatrixDynSize >::allocator_type(static_cast< const std::vector< iDynTree::MatrixDynSize >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__MatrixDynSize_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8138,23 +8249,23 @@ int _wrap_BerdySensors_get_allocator(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_BerdySensors__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor >::size_type arg1 ; +int _wrap_new_MatrixDynSizeVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize >::size_type arg1 ; size_t val1 ; int ecode1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor > *result = 0 ; + std::vector< iDynTree::MatrixDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdySensors",argc,1,1,0)) { + if (!SWIG_check_num_args("new_MatrixDynSizeVector",argc,1,1,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MatrixDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg1 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val1); - result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); + arg1 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val1); + result = (std::vector< iDynTree::MatrixDynSize > *)new std::vector< iDynTree::MatrixDynSize >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8162,20 +8273,20 @@ int _wrap_new_BerdySensors__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_BerdySensors_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_pop_back",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); (arg1)->pop_back(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -8185,28 +8296,28 @@ int _wrap_BerdySensors_pop_back(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_BerdySensors_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::size_type arg2 ; +int _wrap_MatrixDynSizeVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSizeVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + arg2 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val2); (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -8216,37 +8327,37 @@ int _wrap_BerdySensors_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdySensors_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::iterator arg2 ; +int _wrap_MatrixDynSizeVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; int res2 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::iterator result; + std::vector< iDynTree::MatrixDynSize >::iterator result; - if (!SWIG_check_num_args("BerdySensors_erase",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } } - result = std_vector_Sl_iDynTree_BerdySensor_Sg__erase__SWIG_0(arg1,arg2); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + result = std_vector_Sl_iDynTree_MatrixDynSize_Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8255,10 +8366,10 @@ int _wrap_BerdySensors_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdySensors_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::iterator arg2 ; - std::vector< iDynTree::BerdySensor >::iterator arg3 ; +int _wrap_MatrixDynSizeVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::iterator arg2 ; + std::vector< iDynTree::MatrixDynSize >::iterator arg3 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -8266,40 +8377,40 @@ int _wrap_BerdySensors_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArra swig::MatlabSwigIterator *iter3 = 0 ; int res3 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::iterator result; + std::vector< iDynTree::MatrixDynSize >::iterator result; - if (!SWIG_check_num_args("BerdySensors_erase",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_erase",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } } res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res3) || !iter3) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); if (iter_t) { arg3 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } } - result = std_vector_Sl_iDynTree_BerdySensor_Sg__erase__SWIG_1(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + result = std_vector_Sl_iDynTree_MatrixDynSize_Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8308,75 +8419,75 @@ int _wrap_BerdySensors_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdySensors_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_MatrixDynSizeVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_BerdySensors_erase__SWIG_0(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_erase__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_BerdySensors_erase__SWIG_1(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_erase__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_erase'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'MatrixDynSizeVector_erase'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdySensor >::erase(std::vector< iDynTree::BerdySensor >::iterator)\n" - " std::vector< iDynTree::BerdySensor >::erase(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::iterator)\n"); + " std::vector< iDynTree::MatrixDynSize >::erase(std::vector< iDynTree::MatrixDynSize >::iterator)\n" + " std::vector< iDynTree::MatrixDynSize >::erase(std::vector< iDynTree::MatrixDynSize >::iterator,std::vector< iDynTree::MatrixDynSize >::iterator)\n"); return 1; } -int _wrap_new_BerdySensors__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor >::size_type arg1 ; - std::vector< iDynTree::BerdySensor >::value_type *arg2 = 0 ; +int _wrap_new_MatrixDynSizeVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize >::size_type arg1 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg2 = 0 ; size_t val1 ; int ecode1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor > *result = 0 ; + std::vector< iDynTree::MatrixDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdySensors",argc,2,2,0)) { + if (!SWIG_check_num_args("new_MatrixDynSizeVector",argc,2,2,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MatrixDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg1 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + arg1 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_BerdySensors" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_MatrixDynSizeVector" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdySensors" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSizeVector" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2); - result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(arg1,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); + arg2 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp2); + result = (std::vector< iDynTree::MatrixDynSize > *)new std::vector< iDynTree::MatrixDynSize >(arg1,(std::vector< iDynTree::MatrixDynSize >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8384,9 +8495,9 @@ int _wrap_new_BerdySensors__SWIG_3(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_MatrixDynSizeVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_BerdySensors__SWIG_0(resc,resv,argc,argv); + return _wrap_new_MatrixDynSizeVector__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; @@ -8395,15 +8506,15 @@ int _wrap_new_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_BerdySensors__SWIG_2(resc,resv,argc,argv); + return _wrap_new_MatrixDynSizeVector__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_BerdySensors__SWIG_1(resc,resv,argc,argv); + return _wrap_new_MatrixDynSizeVector__SWIG_1(resc,resv,argc,argv); } } if (argc == 2) { @@ -8414,50 +8525,50 @@ int _wrap_new_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_BerdySensors__SWIG_3(resc,resv,argc,argv); + return _wrap_new_MatrixDynSizeVector__SWIG_3(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_BerdySensors'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_MatrixDynSizeVector'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdySensor >::vector()\n" - " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor > const &)\n" - " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor >::size_type)\n" - " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); + " std::vector< iDynTree::MatrixDynSize >::vector()\n" + " std::vector< iDynTree::MatrixDynSize >::vector(std::vector< iDynTree::MatrixDynSize > const &)\n" + " std::vector< iDynTree::MatrixDynSize >::vector(std::vector< iDynTree::MatrixDynSize >::size_type)\n" + " std::vector< iDynTree::MatrixDynSize >::vector(std::vector< iDynTree::MatrixDynSize >::size_type,std::vector< iDynTree::MatrixDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdySensors_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::value_type *arg2 = 0 ; +int _wrap_MatrixDynSizeVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_push_back",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSizeVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2); - (arg1)->push_back((std::vector< iDynTree::BerdySensor >::value_type const &)*arg2); + arg2 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp2); + (arg1)->push_back((std::vector< iDynTree::MatrixDynSize >::value_type const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -8466,23 +8577,23 @@ int _wrap_BerdySensors_push_back(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_BerdySensors_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::value_type *result = 0 ; + std::vector< iDynTree::MatrixDynSize >::value_type *result = 0 ; - if (!SWIG_check_num_args("BerdySensors_front",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_front" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_front" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = (std::vector< iDynTree::BerdySensor >::value_type *) &((std::vector< iDynTree::BerdySensor > const *)arg1)->front(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdySensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = (std::vector< iDynTree::MatrixDynSize >::value_type *) &((std::vector< iDynTree::MatrixDynSize > const *)arg1)->front(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8490,23 +8601,23 @@ int _wrap_BerdySensors_front(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_BerdySensors_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::value_type *result = 0 ; + std::vector< iDynTree::MatrixDynSize >::value_type *result = 0 ; - if (!SWIG_check_num_args("BerdySensors_back",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_back" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = (std::vector< iDynTree::BerdySensor >::value_type *) &((std::vector< iDynTree::BerdySensor > const *)arg1)->back(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdySensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = (std::vector< iDynTree::MatrixDynSize >::value_type *) &((std::vector< iDynTree::MatrixDynSize > const *)arg1)->back(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8514,10 +8625,10 @@ int _wrap_BerdySensors_back(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_BerdySensors_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::size_type arg2 ; - std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; +int _wrap_MatrixDynSizeVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::size_type arg2 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; @@ -8526,28 +8637,28 @@ int _wrap_BerdySensors_assign(int resc, mxArray *resv[], int argc, mxArray *argv int res3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_assign",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_assign" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_assign" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_assign" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSizeVector_assign" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + arg2 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "MatrixDynSizeVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); - (arg1)->assign(arg2,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg3); + arg3 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp3); + (arg1)->assign(arg2,(std::vector< iDynTree::MatrixDynSize >::value_type const &)*arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -8556,10 +8667,10 @@ int _wrap_BerdySensors_assign(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_BerdySensors_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::size_type arg2 ; - std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; +int _wrap_MatrixDynSizeVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::size_type arg2 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; @@ -8568,28 +8679,28 @@ int _wrap_BerdySensors_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr int res3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSizeVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + arg2 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "MatrixDynSizeVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); - (arg1)->resize(arg2,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg3); + arg3 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp3); + (arg1)->resize(arg2,(std::vector< iDynTree::MatrixDynSize >::value_type const &)*arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -8598,10 +8709,10 @@ int _wrap_BerdySensors_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdySensors_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_MatrixDynSizeVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -8609,13 +8720,13 @@ int _wrap_BerdySensors_resize(int resc, mxArray *resv[], int argc, mxArray *argv _v = SWIG_CheckState(res); } if (_v) { - return _wrap_BerdySensors_resize__SWIG_0(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_resize__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -8624,27 +8735,27 @@ int _wrap_BerdySensors_resize(int resc, mxArray *resv[], int argc, mxArray *argv } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdySensors_resize__SWIG_1(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_resize__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'MatrixDynSizeVector_resize'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdySensor >::resize(std::vector< iDynTree::BerdySensor >::size_type)\n" - " std::vector< iDynTree::BerdySensor >::resize(std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); + " std::vector< iDynTree::MatrixDynSize >::resize(std::vector< iDynTree::MatrixDynSize >::size_type)\n" + " std::vector< iDynTree::MatrixDynSize >::resize(std::vector< iDynTree::MatrixDynSize >::size_type,std::vector< iDynTree::MatrixDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdySensors_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::iterator arg2 ; - std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; +int _wrap_MatrixDynSizeVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::iterator arg2 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -8652,37 +8763,37 @@ int _wrap_BerdySensors_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArr void *argp3 ; int res3 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::iterator result; + std::vector< iDynTree::MatrixDynSize >::iterator result; - if (!SWIG_check_num_args("BerdySensors_insert",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "MatrixDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); - result = std_vector_Sl_iDynTree_BerdySensor_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::BerdySensor const &)*arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + arg3 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp3); + result = std_vector_Sl_iDynTree_MatrixDynSize_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::MatrixDynSize const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::MatrixDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -8691,11 +8802,11 @@ int _wrap_BerdySensors_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdySensors_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::iterator arg2 ; - std::vector< iDynTree::BerdySensor >::size_type arg3 ; - std::vector< iDynTree::BerdySensor >::value_type *arg4 = 0 ; +int _wrap_MatrixDynSizeVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::iterator arg2 ; + std::vector< iDynTree::MatrixDynSize >::size_type arg3 ; + std::vector< iDynTree::MatrixDynSize >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -8706,39 +8817,39 @@ int _wrap_BerdySensors_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArr int res4 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_insert",argc,4,4,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "MatrixDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::iterator""'"); } } ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg3 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + arg3 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "BerdySensors_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "MatrixDynSizeVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MatrixDynSizeVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::MatrixDynSize >::value_type const &""'"); } - arg4 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp4); - std_vector_Sl_iDynTree_BerdySensor_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::BerdySensor const &)*arg4); + arg4 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize >::value_type * >(argp4); + std_vector_Sl_iDynTree_MatrixDynSize_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::MatrixDynSize const &)*arg4); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -8747,33 +8858,33 @@ int _wrap_BerdySensors_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdySensors_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_MatrixDynSizeVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdySensors_insert__SWIG_0(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_insert__SWIG_0(resc,resv,argc,argv); } } } } if (argc == 4) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { { int res = SWIG_AsVal_size_t(argv[2], NULL); @@ -8781,46 +8892,46 @@ int _wrap_BerdySensors_insert(int resc, mxArray *resv[], int argc, mxArray *argv } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdySensors_insert__SWIG_1(resc,resv,argc,argv); + return _wrap_MatrixDynSizeVector_insert__SWIG_1(resc,resv,argc,argv); } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_insert'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'MatrixDynSizeVector_insert'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdySensor >::insert(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::value_type const &)\n" - " std::vector< iDynTree::BerdySensor >::insert(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); + " std::vector< iDynTree::MatrixDynSize >::insert(std::vector< iDynTree::MatrixDynSize >::iterator,std::vector< iDynTree::MatrixDynSize >::value_type const &)\n" + " std::vector< iDynTree::MatrixDynSize >::insert(std::vector< iDynTree::MatrixDynSize >::iterator,std::vector< iDynTree::MatrixDynSize >::size_type,std::vector< iDynTree::MatrixDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdySensors_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; - std::vector< iDynTree::BerdySensor >::size_type arg2 ; +int _wrap_MatrixDynSizeVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; + std::vector< iDynTree::MatrixDynSize >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdySensors_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSizeVector_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::MatrixDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + arg2 = static_cast< std::vector< iDynTree::MatrixDynSize >::size_type >(val2); (arg1)->reserve(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -8830,22 +8941,22 @@ int _wrap_BerdySensors_reserve(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_BerdySensors_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_MatrixDynSizeVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdySensor >::size_type result; + std::vector< iDynTree::MatrixDynSize >::size_type result; - if (!SWIG_check_num_args("BerdySensors_capacity",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSizeVector_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSizeVector_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); - result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->capacity(); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); + result = ((std::vector< iDynTree::MatrixDynSize > const *)arg1)->capacity(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -8854,22 +8965,22 @@ int _wrap_BerdySensors_capacity(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_delete_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; +int _wrap_delete_MatrixDynSizeVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::MatrixDynSize > *arg1 = (std::vector< iDynTree::MatrixDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_BerdySensors",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_MatrixDynSizeVector",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_MatrixDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::MatrixDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize > * >(argp1); if (is_owned) { delete arg1; } @@ -8881,29 +8992,29 @@ int _wrap_delete_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_BerdyDynamicVariables_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::value_type result; + std::vector< iDynTree::VectorDynSize >::value_type result; - if (!SWIG_check_num_args("BerdyDynamicVariables_pop",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_pop" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_pop" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); try { - result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__pop(arg1); + result = std_vector_Sl_iDynTree_VectorDynSize_Sg__pop(arg1); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::value_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, SWIG_POINTER_OWN | 0 ); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::VectorDynSize >::value_type(static_cast< const std::vector< iDynTree::VectorDynSize >::value_type& >(result))), SWIGTYPE_p_iDynTree__VectorDynSize, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8911,37 +9022,37 @@ int _wrap_BerdyDynamicVariables_pop(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_BerdyDynamicVariables_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::difference_type arg2 ; +int _wrap_VectorDynSizeVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::value_type result; + std::vector< iDynTree::VectorDynSize >::value_type result; - if (!SWIG_check_num_args("BerdyDynamicVariables_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_brace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_brace" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_brace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSizeVector_brace" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::difference_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::difference_type >(val2); + arg2 = static_cast< std::vector< iDynTree::VectorDynSize >::difference_type >(val2); try { - result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__brace(arg1,arg2); + result = std_vector_Sl_iDynTree_VectorDynSize_Sg__brace(arg1,arg2); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::value_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, SWIG_POINTER_OWN | 0 ); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::VectorDynSize >::value_type(static_cast< const std::vector< iDynTree::VectorDynSize >::value_type& >(result))), SWIGTYPE_p_iDynTree__VectorDynSize, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -8949,10 +9060,10 @@ int _wrap_BerdyDynamicVariables_brace(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdyDynamicVariables_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::difference_type arg3 ; +int _wrap_VectorDynSizeVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::value_type arg2 ; + std::vector< iDynTree::VectorDynSize >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; @@ -8961,32 +9072,32 @@ int _wrap_BerdyDynamicVariables_setbrace(int resc, mxArray *resv[], int argc, mx int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_setbrace",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); { - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSizeVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type""'"); } else { - arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2)); + arg2 = *(reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp2)); } } ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "VectorDynSizeVector_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::difference_type""'"); } - arg3 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::difference_type >(val3); + arg3 = static_cast< std::vector< iDynTree::VectorDynSize >::difference_type >(val3); try { - std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__setbrace(arg1,arg2,arg3); + std_vector_Sl_iDynTree_VectorDynSize_Sg__setbrace(arg1,arg2,arg3); } catch(std::out_of_range &_e) { SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); @@ -9000,35 +9111,35 @@ int _wrap_BerdyDynamicVariables_setbrace(int resc, mxArray *resv[], int argc, mx } -int _wrap_BerdyDynamicVariables_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type arg2 ; +int _wrap_VectorDynSizeVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::value_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_append",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_append" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_append" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); { - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSizeVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type""'"); } else { - arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2)); + arg2 = *(reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp2)); } } - std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__append(arg1,arg2); + std_vector_Sl_iDynTree_VectorDynSize_Sg__append(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -9037,16 +9148,16 @@ int _wrap_BerdyDynamicVariables_append(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_new_BerdyDynamicVariables__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_VectorDynSizeVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; + std::vector< iDynTree::VectorDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,0,0,0)) { + if (!SWIG_check_num_args("new_VectorDynSizeVector",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); + result = (std::vector< iDynTree::VectorDynSize > *)new std::vector< iDynTree::VectorDynSize >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9054,28 +9165,28 @@ int _wrap_new_BerdyDynamicVariables__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_BerdyDynamicVariables__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = 0 ; +int _wrap_new_VectorDynSizeVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = 0 ; int res1 = SWIG_OLDOBJ ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; + std::vector< iDynTree::VectorDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,1,1,0)) { + if (!SWIG_check_num_args("new_VectorDynSizeVector",argc,1,1,0)) { SWIG_fail; } { - std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > > *ptr = (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > > *)0; + std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > *ptr = (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > *)0; res1 = swig::asptr(argv[0], &ptr); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const &""'"); } arg1 = ptr; } - result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >((std::vector< iDynTree::BerdyDynamicVariable > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); + result = (std::vector< iDynTree::VectorDynSize > *)new std::vector< iDynTree::VectorDynSize >((std::vector< iDynTree::VectorDynSize > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; if (SWIG_IsNewObj(res1)) delete arg1; return 0; @@ -9085,22 +9196,22 @@ int _wrap_new_BerdyDynamicVariables__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_BerdyDynamicVariables_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("BerdyDynamicVariables_empty",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_empty" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_empty" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = (bool)((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->empty(); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = (bool)((std::vector< iDynTree::VectorDynSize > const *)arg1)->empty(); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -9109,22 +9220,22 @@ int _wrap_BerdyDynamicVariables_empty(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdyDynamicVariables_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::size_type result; + std::vector< iDynTree::VectorDynSize >::size_type result; - if (!SWIG_check_num_args("BerdyDynamicVariables_size",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_size" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_size" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->size(); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = ((std::vector< iDynTree::VectorDynSize > const *)arg1)->size(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -9133,31 +9244,31 @@ int _wrap_BerdyDynamicVariables_size(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdyDynamicVariables_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable > *arg2 = 0 ; +int _wrap_VectorDynSizeVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_swap",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_swap",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_swap" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_swap" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSizeVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize > &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize > &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp2); + arg2 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp2); (arg1)->swap(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -9167,23 +9278,23 @@ int _wrap_BerdyDynamicVariables_swap(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdyDynamicVariables_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::iterator result; + std::vector< iDynTree::VectorDynSize >::iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_begin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_begin" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); result = (arg1)->begin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9192,23 +9303,23 @@ int _wrap_BerdyDynamicVariables_begin(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdyDynamicVariables_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::iterator result; + std::vector< iDynTree::VectorDynSize >::iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_end",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_end" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_end" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); result = (arg1)->end(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9217,23 +9328,23 @@ int _wrap_BerdyDynamicVariables_end(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_BerdyDynamicVariables_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator result; + std::vector< iDynTree::VectorDynSize >::reverse_iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_rbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); result = (arg1)->rbegin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::reverse_iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9242,23 +9353,23 @@ int _wrap_BerdyDynamicVariables_rbegin(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_BerdyDynamicVariables_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator result; + std::vector< iDynTree::VectorDynSize >::reverse_iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_rend",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_rend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_rend" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_rend" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); result = (arg1)->rend(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator & >(result)), + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::reverse_iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9267,20 +9378,20 @@ int _wrap_BerdyDynamicVariables_rend(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdyDynamicVariables_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_clear",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_clear",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_clear" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_clear" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); (arg1)->clear(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -9290,23 +9401,23 @@ int _wrap_BerdyDynamicVariables_clear(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdyDynamicVariables_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - SwigValueWrapper< std::allocator< iDynTree::BerdyDynamicVariable > > result; + SwigValueWrapper< std::allocator< iDynTree::VectorDynSize > > result; - if (!SWIG_check_num_args("BerdyDynamicVariables_get_allocator",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_get_allocator",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->get_allocator(); - _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::allocator_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__BerdyDynamicVariable_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = ((std::vector< iDynTree::VectorDynSize > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::VectorDynSize >::allocator_type(static_cast< const std::vector< iDynTree::VectorDynSize >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__VectorDynSize_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9314,23 +9425,23 @@ int _wrap_BerdyDynamicVariables_get_allocator(int resc, mxArray *resv[], int arg } -int _wrap_new_BerdyDynamicVariables__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg1 ; +int _wrap_new_VectorDynSizeVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize >::size_type arg1 ; size_t val1 ; int ecode1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; + std::vector< iDynTree::VectorDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,1,1,0)) { + if (!SWIG_check_num_args("new_VectorDynSizeVector",argc,1,1,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_VectorDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg1 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val1); - result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); + arg1 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val1); + result = (std::vector< iDynTree::VectorDynSize > *)new std::vector< iDynTree::VectorDynSize >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9338,20 +9449,20 @@ int _wrap_new_BerdyDynamicVariables__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_BerdyDynamicVariables_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_pop_back",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); (arg1)->pop_back(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -9361,28 +9472,28 @@ int _wrap_BerdyDynamicVariables_pop_back(int resc, mxArray *resv[], int argc, mx } -int _wrap_BerdyDynamicVariables_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; +int _wrap_VectorDynSizeVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSizeVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + arg2 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val2); (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -9392,37 +9503,37 @@ int _wrap_BerdyDynamicVariables_resize__SWIG_0(int resc, mxArray *resv[], int ar } -int _wrap_BerdyDynamicVariables_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; +int _wrap_VectorDynSizeVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; int res2 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::iterator result; + std::vector< iDynTree::VectorDynSize >::iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_erase",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } } - result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__erase__SWIG_0(arg1,arg2); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + result = std_vector_Sl_iDynTree_VectorDynSize_Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9431,10 +9542,10 @@ int _wrap_BerdyDynamicVariables_erase__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_BerdyDynamicVariables_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::iterator arg3 ; +int _wrap_VectorDynSizeVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::iterator arg2 ; + std::vector< iDynTree::VectorDynSize >::iterator arg3 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -9442,40 +9553,40 @@ int _wrap_BerdyDynamicVariables_erase__SWIG_1(int resc, mxArray *resv[], int arg swig::MatlabSwigIterator *iter3 = 0 ; int res3 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::iterator result; + std::vector< iDynTree::VectorDynSize >::iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_erase",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_erase",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } } res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res3) || !iter3) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); if (iter_t) { arg3 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } } - result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__erase__SWIG_1(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + result = std_vector_Sl_iDynTree_VectorDynSize_Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9484,75 +9595,75 @@ int _wrap_BerdyDynamicVariables_erase__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_BerdyDynamicVariables_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_VectorDynSizeVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_BerdyDynamicVariables_erase__SWIG_0(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_erase__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_BerdyDynamicVariables_erase__SWIG_1(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_erase__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_erase'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSizeVector_erase'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdyDynamicVariable >::erase(std::vector< iDynTree::BerdyDynamicVariable >::iterator)\n" - " std::vector< iDynTree::BerdyDynamicVariable >::erase(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::iterator)\n"); + " std::vector< iDynTree::VectorDynSize >::erase(std::vector< iDynTree::VectorDynSize >::iterator)\n" + " std::vector< iDynTree::VectorDynSize >::erase(std::vector< iDynTree::VectorDynSize >::iterator,std::vector< iDynTree::VectorDynSize >::iterator)\n"); return 1; } -int _wrap_new_BerdyDynamicVariables__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg1 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg2 = 0 ; +int _wrap_new_VectorDynSizeVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize >::size_type arg1 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg2 = 0 ; size_t val1 ; int ecode1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; + std::vector< iDynTree::VectorDynSize > *result = 0 ; - if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,2,2,0)) { + if (!SWIG_check_num_args("new_VectorDynSizeVector",argc,2,2,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_VectorDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg1 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + arg1 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_BerdyDynamicVariables" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_VectorDynSizeVector" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdyDynamicVariables" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSizeVector" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2); - result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(arg1,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); + arg2 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp2); + result = (std::vector< iDynTree::VectorDynSize > *)new std::vector< iDynTree::VectorDynSize >(arg1,(std::vector< iDynTree::VectorDynSize >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9560,9 +9671,9 @@ int _wrap_new_BerdyDynamicVariables__SWIG_3(int resc, mxArray *resv[], int argc, } -int _wrap_new_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_VectorDynSizeVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_BerdyDynamicVariables__SWIG_0(resc,resv,argc,argv); + return _wrap_new_VectorDynSizeVector__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; @@ -9571,15 +9682,15 @@ int _wrap_new_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_BerdyDynamicVariables__SWIG_2(resc,resv,argc,argv); + return _wrap_new_VectorDynSizeVector__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_BerdyDynamicVariables__SWIG_1(resc,resv,argc,argv); + return _wrap_new_VectorDynSizeVector__SWIG_1(resc,resv,argc,argv); } } if (argc == 2) { @@ -9590,50 +9701,50 @@ int _wrap_new_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_BerdyDynamicVariables__SWIG_3(resc,resv,argc,argv); + return _wrap_new_VectorDynSizeVector__SWIG_3(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_BerdyDynamicVariables'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_VectorDynSizeVector'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdyDynamicVariable >::vector()\n" - " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable > const &)\n" - " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable >::size_type)\n" - " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); + " std::vector< iDynTree::VectorDynSize >::vector()\n" + " std::vector< iDynTree::VectorDynSize >::vector(std::vector< iDynTree::VectorDynSize > const &)\n" + " std::vector< iDynTree::VectorDynSize >::vector(std::vector< iDynTree::VectorDynSize >::size_type)\n" + " std::vector< iDynTree::VectorDynSize >::vector(std::vector< iDynTree::VectorDynSize >::size_type,std::vector< iDynTree::VectorDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdyDynamicVariables_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg2 = 0 ; +int _wrap_VectorDynSizeVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_push_back",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSizeVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2); - (arg1)->push_back((std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg2); + arg2 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp2); + (arg1)->push_back((std::vector< iDynTree::VectorDynSize >::value_type const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -9642,23 +9753,23 @@ int _wrap_BerdyDynamicVariables_push_back(int resc, mxArray *resv[], int argc, m } -int _wrap_BerdyDynamicVariables_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *result = 0 ; + std::vector< iDynTree::VectorDynSize >::value_type *result = 0 ; - if (!SWIG_check_num_args("BerdyDynamicVariables_front",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_front" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_front" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = (std::vector< iDynTree::BerdyDynamicVariable >::value_type *) &((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->front(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = (std::vector< iDynTree::VectorDynSize >::value_type *) &((std::vector< iDynTree::VectorDynSize > const *)arg1)->front(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9666,23 +9777,23 @@ int _wrap_BerdyDynamicVariables_front(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_BerdyDynamicVariables_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *result = 0 ; + std::vector< iDynTree::VectorDynSize >::value_type *result = 0 ; - if (!SWIG_check_num_args("BerdyDynamicVariables_back",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_back" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = (std::vector< iDynTree::BerdyDynamicVariable >::value_type *) &((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->back(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = (std::vector< iDynTree::VectorDynSize >::value_type *) &((std::vector< iDynTree::VectorDynSize > const *)arg1)->back(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -9690,10 +9801,10 @@ int _wrap_BerdyDynamicVariables_back(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_BerdyDynamicVariables_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; +int _wrap_VectorDynSizeVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::size_type arg2 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; @@ -9702,28 +9813,28 @@ int _wrap_BerdyDynamicVariables_assign(int resc, mxArray *resv[], int argc, mxAr int res3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_assign",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_assign" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_assign" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_assign" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSizeVector_assign" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + arg2 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "VectorDynSizeVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); - (arg1)->assign(arg2,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg3); + arg3 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp3); + (arg1)->assign(arg2,(std::vector< iDynTree::VectorDynSize >::value_type const &)*arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -9732,10 +9843,10 @@ int _wrap_BerdyDynamicVariables_assign(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_BerdyDynamicVariables_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; +int _wrap_VectorDynSizeVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::size_type arg2 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; @@ -9744,28 +9855,28 @@ int _wrap_BerdyDynamicVariables_resize__SWIG_1(int resc, mxArray *resv[], int ar int res3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSizeVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + arg2 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "VectorDynSizeVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); - (arg1)->resize(arg2,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg3); + arg3 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp3); + (arg1)->resize(arg2,(std::vector< iDynTree::VectorDynSize >::value_type const &)*arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -9774,10 +9885,10 @@ int _wrap_BerdyDynamicVariables_resize__SWIG_1(int resc, mxArray *resv[], int ar } -int _wrap_BerdyDynamicVariables_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_VectorDynSizeVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -9785,13 +9896,13 @@ int _wrap_BerdyDynamicVariables_resize(int resc, mxArray *resv[], int argc, mxAr _v = SWIG_CheckState(res); } if (_v) { - return _wrap_BerdyDynamicVariables_resize__SWIG_0(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_resize__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -9800,27 +9911,27 @@ int _wrap_BerdyDynamicVariables_resize(int resc, mxArray *resv[], int argc, mxAr } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdyDynamicVariables_resize__SWIG_1(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_resize__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSizeVector_resize'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdyDynamicVariable >::resize(std::vector< iDynTree::BerdyDynamicVariable >::size_type)\n" - " std::vector< iDynTree::BerdyDynamicVariable >::resize(std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); + " std::vector< iDynTree::VectorDynSize >::resize(std::vector< iDynTree::VectorDynSize >::size_type)\n" + " std::vector< iDynTree::VectorDynSize >::resize(std::vector< iDynTree::VectorDynSize >::size_type,std::vector< iDynTree::VectorDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdyDynamicVariables_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; +int _wrap_VectorDynSizeVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::iterator arg2 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -9828,37 +9939,37 @@ int _wrap_BerdyDynamicVariables_insert__SWIG_0(int resc, mxArray *resv[], int ar void *argp3 ; int res3 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::iterator result; + std::vector< iDynTree::VectorDynSize >::iterator result; - if (!SWIG_check_num_args("BerdyDynamicVariables_insert",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "VectorDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); - result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::BerdyDynamicVariable const &)*arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + arg3 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp3); + result = std_vector_Sl_iDynTree_VectorDynSize_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::VectorDynSize const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::VectorDynSize >::iterator & >(result)), swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; @@ -9867,11 +9978,11 @@ int _wrap_BerdyDynamicVariables_insert__SWIG_0(int resc, mxArray *resv[], int ar } -int _wrap_BerdyDynamicVariables_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg3 ; - std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg4 = 0 ; +int _wrap_VectorDynSizeVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::iterator arg2 ; + std::vector< iDynTree::VectorDynSize >::size_type arg3 ; + std::vector< iDynTree::VectorDynSize >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; swig::MatlabSwigIterator *iter2 = 0 ; @@ -9882,39 +9993,39 @@ int _wrap_BerdyDynamicVariables_insert__SWIG_1(int resc, mxArray *resv[], int ar int res4 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_insert",argc,4,4,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); if (iter_t) { arg2 = iter_t->get_current(); } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "VectorDynSizeVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::iterator""'"); } } ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "VectorDynSizeVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg3 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + arg3 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "BerdyDynamicVariables_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "VectorDynSizeVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "VectorDynSizeVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::VectorDynSize >::value_type const &""'"); } - arg4 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp4); - std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::BerdyDynamicVariable const &)*arg4); + arg4 = reinterpret_cast< std::vector< iDynTree::VectorDynSize >::value_type * >(argp4); + std_vector_Sl_iDynTree_VectorDynSize_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::VectorDynSize const &)*arg4); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -9923,33 +10034,33 @@ int _wrap_BerdyDynamicVariables_insert__SWIG_1(int resc, mxArray *resv[], int ar } -int _wrap_BerdyDynamicVariables_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_VectorDynSizeVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdyDynamicVariables_insert__SWIG_0(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_insert__SWIG_0(resc,resv,argc,argv); } } } } if (argc == 4) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + int res = swig::asptr(argv[0], (std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > >**)(0)); _v = SWIG_CheckState(res); if (_v) { swig::MatlabSwigIterator *iter = 0; int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { { int res = SWIG_AsVal_size_t(argv[2], NULL); @@ -9957,46 +10068,46 @@ int _wrap_BerdyDynamicVariables_insert(int resc, mxArray *resv[], int argc, mxAr } if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdyDynamicVariables_insert__SWIG_1(resc,resv,argc,argv); + return _wrap_VectorDynSizeVector_insert__SWIG_1(resc,resv,argc,argv); } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_insert'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSizeVector_insert'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::BerdyDynamicVariable >::insert(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n" - " std::vector< iDynTree::BerdyDynamicVariable >::insert(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); + " std::vector< iDynTree::VectorDynSize >::insert(std::vector< iDynTree::VectorDynSize >::iterator,std::vector< iDynTree::VectorDynSize >::value_type const &)\n" + " std::vector< iDynTree::VectorDynSize >::insert(std::vector< iDynTree::VectorDynSize >::iterator,std::vector< iDynTree::VectorDynSize >::size_type,std::vector< iDynTree::VectorDynSize >::value_type const &)\n"); return 1; } -int _wrap_BerdyDynamicVariables_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; - std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; +int _wrap_VectorDynSizeVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; + std::vector< iDynTree::VectorDynSize >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("BerdyDynamicVariables_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSizeVector_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::VectorDynSize >::size_type""'"); } - arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + arg2 = static_cast< std::vector< iDynTree::VectorDynSize >::size_type >(val2); (arg1)->reserve(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -10006,22 +10117,22 @@ int _wrap_BerdyDynamicVariables_reserve(int resc, mxArray *resv[], int argc, mxA } -int _wrap_BerdyDynamicVariables_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_VectorDynSizeVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::BerdyDynamicVariable >::size_type result; + std::vector< iDynTree::VectorDynSize >::size_type result; - if (!SWIG_check_num_args("BerdyDynamicVariables_capacity",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSizeVector_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSizeVector_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); - result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->capacity(); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); + result = ((std::vector< iDynTree::VectorDynSize > const *)arg1)->capacity(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -10030,22 +10141,22 @@ int _wrap_BerdyDynamicVariables_capacity(int resc, mxArray *resv[], int argc, mx } -int _wrap_delete_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; +int _wrap_delete_VectorDynSizeVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::VectorDynSize > *arg1 = (std::vector< iDynTree::VectorDynSize > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_BerdyDynamicVariables",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_VectorDynSizeVector",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_VectorDynSizeVector" "', argument " "1"" of type '" "std::vector< iDynTree::VectorDynSize > *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::VectorDynSize > * >(argp1); if (is_owned) { delete arg1; } @@ -10057,125 +10168,111 @@ int _wrap_delete_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_reportInfo(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - char *arg1 = (char *) 0 ; - char *arg2 = (char *) 0 ; - char *arg3 = (char *) 0 ; - int res1 ; - char *buf1 = 0 ; - int alloc1 = 0 ; - int res2 ; - char *buf2 = 0 ; - int alloc2 = 0 ; - int res3 ; - char *buf3 = 0 ; - int alloc3 = 0 ; +int _wrap_IndexVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; + std::vector< ::ptrdiff_t >::value_type result; - if (!SWIG_check_num_args("reportInfo",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_AsCharPtrAndSize(argv[0], &buf1, NULL, &alloc1); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "reportInfo" "', argument " "1"" of type '" "char const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_pop" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< char * >(buf1); - res2 = SWIG_AsCharPtrAndSize(argv[1], &buf2, NULL, &alloc2); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "reportInfo" "', argument " "2"" of type '" "char const *""'"); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + try { + result = std_vector_Sl_std_ptrdiff_t_Sg__pop(arg1); } - arg2 = reinterpret_cast< char * >(buf2); - res3 = SWIG_AsCharPtrAndSize(argv[2], &buf3, NULL, &alloc3); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "reportInfo" "', argument " "3"" of type '" "char const *""'"); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - arg3 = reinterpret_cast< char * >(buf3); - iDynTree::reportInfo((char const *)arg1,(char const *)arg2,(char const *)arg3); - _out = (mxArray*)0; + + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; - if (alloc1 == SWIG_NEWOBJ) delete[] buf1; - if (alloc2 == SWIG_NEWOBJ) delete[] buf2; - if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 0; fail: - if (alloc1 == SWIG_NEWOBJ) delete[] buf1; - if (alloc2 == SWIG_NEWOBJ) delete[] buf2; - if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 1; } -int _wrap_reportDebug(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - char *arg1 = (char *) 0 ; - char *arg2 = (char *) 0 ; - char *arg3 = (char *) 0 ; - int res1 ; - char *buf1 = 0 ; - int alloc1 = 0 ; - int res2 ; - char *buf2 = 0 ; - int alloc2 = 0 ; - int res3 ; - char *buf3 = 0 ; - int alloc3 = 0 ; +int _wrap_IndexVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::difference_type arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + std::vector< ::ptrdiff_t >::value_type result; - if (!SWIG_check_num_args("reportDebug",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_AsCharPtrAndSize(argv[0], &buf1, NULL, &alloc1); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "reportDebug" "', argument " "1"" of type '" "char const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_brace" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< char * >(buf1); - res2 = SWIG_AsCharPtrAndSize(argv[1], &buf2, NULL, &alloc2); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "reportDebug" "', argument " "2"" of type '" "char const *""'"); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_brace" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::difference_type""'"); + } + arg2 = static_cast< std::vector< ::ptrdiff_t >::difference_type >(val2); + try { + result = std_vector_Sl_std_ptrdiff_t_Sg__brace(arg1,arg2); } - arg2 = reinterpret_cast< char * >(buf2); - res3 = SWIG_AsCharPtrAndSize(argv[2], &buf3, NULL, &alloc3); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "reportDebug" "', argument " "3"" of type '" "char const *""'"); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - arg3 = reinterpret_cast< char * >(buf3); - iDynTree::reportDebug((char const *)arg1,(char const *)arg2,(char const *)arg3); - _out = (mxArray*)0; + + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; - if (alloc1 == SWIG_NEWOBJ) delete[] buf1; - if (alloc2 == SWIG_NEWOBJ) delete[] buf2; - if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 0; fail: - if (alloc1 == SWIG_NEWOBJ) delete[] buf1; - if (alloc2 == SWIG_NEWOBJ) delete[] buf2; - if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 1; } -int _wrap_IndexRange_offset_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; - std::ptrdiff_t arg2 ; +int _wrap_IndexVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::value_type arg2 ; + std::vector< ::ptrdiff_t >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("IndexRange_offset_set",argc,2,2,0)) { + if (!SWIG_check_num_args("IndexVector_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_offset_set" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_setbrace" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexRange_offset_set" "', argument " "2"" of type '" "std::ptrdiff_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_setbrace" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); } - arg2 = static_cast< std::ptrdiff_t >(val2); - if (arg1) (arg1)->offset = arg2; + arg2 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IndexVector_setbrace" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::difference_type""'"); + } + arg3 = static_cast< std::vector< ::ptrdiff_t >::difference_type >(val3); + try { + std_vector_Sl_std_ptrdiff_t_Sg__setbrace(arg1,arg2,arg3); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -10184,23 +10281,30 @@ int _wrap_IndexRange_offset_set(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_IndexRange_offset_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; +int _wrap_IndexVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::value_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::ptrdiff_t result; - if (!SWIG_check_num_args("IndexRange_offset_get",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_offset_get" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_append" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); - result = ((arg1)->offset); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_append" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); + } + arg2 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val2); + std_vector_Sl_std_ptrdiff_t_Sg__append(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10208,54 +10312,71 @@ int _wrap_IndexRange_offset_get(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_IndexRange_size_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; - std::ptrdiff_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; +int _wrap_new_IndexVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + std::vector< std::ptrdiff_t > *result = 0 ; - if (!SWIG_check_num_args("IndexRange_size_set",argc,2,2,0)) { + if (!SWIG_check_num_args("new_IndexVector",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_size_set" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); + (void)argv; + result = (std::vector< std::ptrdiff_t > *)new std::vector< std::ptrdiff_t >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_IndexVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = 0 ; + int res1 = SWIG_OLDOBJ ; + mxArray * _out; + std::vector< std::ptrdiff_t > *result = 0 ; + + if (!SWIG_check_num_args("new_IndexVector",argc,1,1,0)) { + SWIG_fail; } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexRange_size_set" "', argument " "2"" of type '" "std::ptrdiff_t""'"); - } - arg2 = static_cast< std::ptrdiff_t >(val2); - if (arg1) (arg1)->size = arg2; - _out = (mxArray*)0; + { + std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > > *ptr = (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > > *)0; + res1 = swig::asptr(argv[0], &ptr); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_IndexVector" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_IndexVector" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const &""'"); + } + arg1 = ptr; + } + result = (std::vector< std::ptrdiff_t > *)new std::vector< std::ptrdiff_t >((std::vector< std::ptrdiff_t > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res1)) delete arg1; return 0; fail: + if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_IndexRange_size_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; +int _wrap_IndexVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::ptrdiff_t result; + bool result; - if (!SWIG_check_num_args("IndexRange_size_get",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_size_get" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_empty" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); - result = ((arg1)->size); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (bool)((std::vector< std::ptrdiff_t > const *)arg1)->empty(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10263,23 +10384,23 @@ int _wrap_IndexRange_size_get(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_IndexRange_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; +int _wrap_IndexVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - bool result; + std::vector< ::ptrdiff_t >::size_type result; - if (!SWIG_check_num_args("IndexRange_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_isValid" "', argument " "1"" of type '" "iDynTree::IndexRange const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_size" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); - result = (bool)((iDynTree::IndexRange const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = ((std::vector< std::ptrdiff_t > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10287,16 +10408,33 @@ int _wrap_IndexRange_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_IndexRange_InvalidRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_IndexVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< std::ptrdiff_t > *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::IndexRange result; - if (!SWIG_check_num_args("IndexRange_InvalidRange",argc,0,0,0)) { + if (!SWIG_check_num_args("IndexVector_swap",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::IndexRange::InvalidRange(); - _out = SWIG_NewPointerObj((new iDynTree::IndexRange(static_cast< const iDynTree::IndexRange& >(result))), SWIGTYPE_p_iDynTree__IndexRange, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_swap" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IndexVector_swap" "', argument " "2"" of type '" "std::vector< std::ptrdiff_t > &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IndexVector_swap" "', argument " "2"" of type '" "std::vector< std::ptrdiff_t > &""'"); + } + arg2 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp2); + (arg1)->swap(*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10304,16 +10442,24 @@ int _wrap_IndexRange_InvalidRange(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_IndexVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::IndexRange *result = 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > result; - if (!SWIG_check_num_args("new_IndexRange",argc,0,0,0)) { + if (!SWIG_check_num_args("IndexVector_begin",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::IndexRange *)new iDynTree::IndexRange(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IndexRange, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_begin" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (arg1)->begin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10321,26 +10467,24 @@ int _wrap_new_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; +int _wrap_IndexVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > result; - int is_owned; - if (!SWIG_check_num_args("delete_IndexRange",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_end",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_IndexRange" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); - } - arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_end" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (arg1)->end(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10348,43 +10492,24 @@ int _wrap_delete_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_checkDoublesAreEqual__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = 0 ; - double *arg2 = 0 ; - double arg3 ; - double temp1 ; - double val1 ; - int ecode1 = 0 ; - double temp2 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_IndexVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - bool result; + SwigValueWrapper< std::vector< ::ptrdiff_t >::reverse_iterator > result; - if (!SWIG_check_num_args("checkDoublesAreEqual",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_rbegin",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "checkDoublesAreEqual" "', argument " "1"" of type '" "double""'"); - } - temp1 = static_cast< double >(val1); - arg1 = &temp1; - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "checkDoublesAreEqual" "', argument " "2"" of type '" "double""'"); - } - temp2 = static_cast< double >(val2); - arg2 = &temp2; - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "checkDoublesAreEqual" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)iDynTree::checkDoublesAreEqual((double const &)*arg1,(double const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_rbegin" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (arg1)->rbegin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10392,35 +10517,24 @@ int _wrap_checkDoublesAreEqual__SWIG_0(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_checkDoublesAreEqual__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = 0 ; - double *arg2 = 0 ; - double temp1 ; - double val1 ; - int ecode1 = 0 ; - double temp2 ; - double val2 ; - int ecode2 = 0 ; +int _wrap_IndexVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - bool result; + SwigValueWrapper< std::vector< ::ptrdiff_t >::reverse_iterator > result; - if (!SWIG_check_num_args("checkDoublesAreEqual",argc,2,2,0)) { + if (!SWIG_check_num_args("IndexVector_rend",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "checkDoublesAreEqual" "', argument " "1"" of type '" "double""'"); - } - temp1 = static_cast< double >(val1); - arg1 = &temp1; - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "checkDoublesAreEqual" "', argument " "2"" of type '" "double""'"); - } - temp2 = static_cast< double >(val2); - arg2 = &temp2; - result = (bool)iDynTree::checkDoublesAreEqual((double const &)*arg1,(double const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_rend" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (arg1)->rend(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10428,64 +10542,46 @@ int _wrap_checkDoublesAreEqual__SWIG_1(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_checkDoublesAreEqual(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_checkDoublesAreEqual__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_IndexVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IndexVector_clear",argc,1,1,0)) { + SWIG_fail; } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_checkDoublesAreEqual__SWIG_0(resc,resv,argc,argv); - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_clear" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'checkDoublesAreEqual'." - " Possible C/C++ prototypes are:\n" - " iDynTree::checkDoublesAreEqual(double const &,double const &,double)\n" - " iDynTree::checkDoublesAreEqual(double const &,double const &)\n"); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + (arg1)->clear(); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_new_MatrixDynSize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_IndexVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::MatrixDynSize *result = 0 ; + SwigValueWrapper< std::allocator< ::ptrdiff_t > > result; - if (!SWIG_check_num_args("new_MatrixDynSize",argc,0,0,0)) { + if (!SWIG_check_num_args("IndexVector_get_allocator",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_get_allocator" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = ((std::vector< std::ptrdiff_t > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< ::ptrdiff_t >::allocator_type(static_cast< const std::vector< ::ptrdiff_t >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_std__ptrdiff_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10493,31 +10589,23 @@ int _wrap_new_MatrixDynSize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_MatrixDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; +int _wrap_new_IndexVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< ::ptrdiff_t >::size_type arg1 ; size_t val1 ; int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::MatrixDynSize *result = 0 ; + std::vector< std::ptrdiff_t > *result = 0 ; - if (!SWIG_check_num_args("new_MatrixDynSize",argc,2,2,0)) { + if (!SWIG_check_num_args("new_IndexVector",argc,1,1,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_MatrixDynSize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_IndexVector" "', argument " "1"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); + arg1 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val1); + result = (std::vector< std::ptrdiff_t > *)new std::vector< std::ptrdiff_t >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10525,39 +10613,53 @@ int _wrap_new_MatrixDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_MatrixDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_IndexVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IndexVector_pop_back",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_pop_back" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + (arg1)->pop_back(); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IndexVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixDynSize *result = 0 ; - if (!SWIG_check_num_args("new_MatrixDynSize",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_resize" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< double * >(argp1); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_MatrixDynSize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_MatrixDynSize" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_resize" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); + arg2 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10565,26 +10667,38 @@ int _wrap_new_MatrixDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_MatrixDynSize__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = 0 ; - void *argp1 ; +int _wrap_IndexVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; mxArray * _out; - iDynTree::MatrixDynSize *result = 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > result; - if (!SWIG_check_num_args("new_MatrixDynSize",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_erase" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const &""'"); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize((iDynTree::MatrixDynSize const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); + result = std_vector_Sl_std_ptrdiff_t_Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10592,29 +10706,52 @@ int _wrap_new_MatrixDynSize__SWIG_3(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_MatrixDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; +int _wrap_IndexVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > arg2 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > arg3 ; + void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + swig::MatlabSwigIterator *iter3 = 0 ; + int res3 ; mxArray * _out; - iDynTree::MatrixDynSize *result = 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > result; - if (!SWIG_check_num_args("new_MatrixDynSize",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_erase",argc,3,3,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_erase" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); } } - result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); + res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res3) || !iter3) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + if (iter_t) { + arg3 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_erase" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } + } + result = std_vector_Sl_std_ptrdiff_t_Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10622,96 +10759,155 @@ int _wrap_new_MatrixDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_MatrixDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_MatrixDynSize__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_IndexVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_MatrixDynSize__SWIG_3(resc,resv,argc,argv); + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_IndexVector_erase__SWIG_0(resc,resv,argc,argv); + } } } - if (argc == 1) { + if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_MatrixDynSize__SWIG_4(resc,resv,argc,argv); + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_IndexVector_erase__SWIG_1(resc,resv,argc,argv); + } + } } } - if (argc == 2) { + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'IndexVector_erase'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::ptrdiff_t >::erase(std::vector< ::ptrdiff_t >::iterator)\n" + " std::vector< std::ptrdiff_t >::erase(std::vector< ::ptrdiff_t >::iterator,std::vector< ::ptrdiff_t >::iterator)\n"); + return 1; +} + + +int _wrap_new_IndexVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< ::ptrdiff_t >::size_type arg1 ; + std::vector< ::ptrdiff_t >::value_type *arg2 = 0 ; + size_t val1 ; + int ecode1 = 0 ; + std::vector< ::ptrdiff_t >::value_type temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + std::vector< std::ptrdiff_t > *result = 0 ; + + if (!SWIG_check_num_args("new_IndexVector",argc,2,2,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_IndexVector" "', argument " "1"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); + } + arg1 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_IndexVector" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); + } + temp2 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val2); + arg2 = &temp2; + result = (std::vector< std::ptrdiff_t > *)new std::vector< std::ptrdiff_t >(arg1,(std::vector< ::ptrdiff_t >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_IndexVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_IndexVector__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; { int res = SWIG_AsVal_size_t(argv[0], NULL); _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_MatrixDynSize__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_IndexVector__SWIG_2(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_IndexVector__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_MatrixDynSize__SWIG_2(resc,resv,argc,argv); - } + return _wrap_new_IndexVector__SWIG_3(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_MatrixDynSize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_IndexVector'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixDynSize::MatrixDynSize()\n" - " iDynTree::MatrixDynSize::MatrixDynSize(std::size_t,std::size_t)\n" - " iDynTree::MatrixDynSize::MatrixDynSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixDynSize::MatrixDynSize(iDynTree::MatrixDynSize const &)\n" - " iDynTree::MatrixDynSize::MatrixDynSize(iDynTree::MatrixView< double const >)\n"); + " std::vector< std::ptrdiff_t >::vector()\n" + " std::vector< std::ptrdiff_t >::vector(std::vector< std::ptrdiff_t > const &)\n" + " std::vector< std::ptrdiff_t >::vector(std::vector< ::ptrdiff_t >::size_type)\n" + " std::vector< std::ptrdiff_t >::vector(std::vector< ::ptrdiff_t >::size_type,std::vector< ::ptrdiff_t >::value_type const &)\n"); return 1; } -int _wrap_delete_MatrixDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_IndexVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + std::vector< ::ptrdiff_t >::value_type temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_MatrixDynSize",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_push_back",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_push_back" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_push_back" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); + } + temp2 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val2); + arg2 = &temp2; + (arg1)->push_back((std::vector< ::ptrdiff_t >::value_type const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -10720,39 +10916,88 @@ int _wrap_delete_MatrixDynSize(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_MatrixDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_IndexVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::vector< ::ptrdiff_t >::value_type *result = 0 ; + + if (!SWIG_check_num_args("IndexVector_front",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_front" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (std::vector< ::ptrdiff_t >::value_type *) &((std::vector< std::ptrdiff_t > const *)arg1)->front(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(*result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IndexVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::vector< ::ptrdiff_t >::value_type *result = 0 ; + + if (!SWIG_check_num_args("IndexVector_back",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_back" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = (std::vector< ::ptrdiff_t >::value_type *) &((std::vector< std::ptrdiff_t > const *)arg1)->back(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(*result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IndexVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::size_type arg2 ; + std::vector< ::ptrdiff_t >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; + std::vector< ::ptrdiff_t >::value_type temp3 ; + ptrdiff_t val3 ; int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("MatrixDynSize_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_paren" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_assign" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_assign" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + arg2 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IndexVector_assign" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixDynSize const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + temp3 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val3); + arg3 = &temp3; + (arg1)->assign(arg2,(std::vector< ::ptrdiff_t >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10760,39 +11005,40 @@ int _wrap_MatrixDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_MatrixDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_IndexVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::size_type arg2 ; + std::vector< ::ptrdiff_t >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; + std::vector< ::ptrdiff_t >::value_type temp3 ; + ptrdiff_t val3 ; int ecode3 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("MatrixDynSize_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_paren" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_resize" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_resize" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + arg2 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IndexVector_resize" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + temp3 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val3); + arg3 = &temp3; + (arg1)->resize(arg2,(std::vector< ::ptrdiff_t >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10800,11 +11046,10 @@ int _wrap_MatrixDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_MatrixDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_IndexVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -10812,20 +11057,13 @@ int _wrap_MatrixDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_MatrixDynSize_paren__SWIG_0(resc,resv,argc,argv); - } + return _wrap_IndexVector_resize__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -10834,57 +11072,66 @@ int _wrap_MatrixDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv } if (_v) { { - int res = SWIG_AsVal_size_t(argv[2], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_MatrixDynSize_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_IndexVector_resize__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'MatrixDynSize_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'IndexVector_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixDynSize::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixDynSize::operator ()(std::size_t const,std::size_t const)\n"); + " std::vector< std::ptrdiff_t >::resize(std::vector< ::ptrdiff_t >::size_type)\n" + " std::vector< std::ptrdiff_t >::resize(std::vector< ::ptrdiff_t >::size_type,std::vector< ::ptrdiff_t >::value_type const &)\n"); return 1; } -int _wrap_MatrixDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_IndexVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > arg2 ; + std::vector< ::ptrdiff_t >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + std::vector< ::ptrdiff_t >::value_type temp3 ; + ptrdiff_t val3 ; int ecode3 = 0 ; mxArray * _out; - double result; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > result; - if (!SWIG_check_num_args("MatrixDynSize_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("IndexVector_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_getVal" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_insert" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_insert" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_insert" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_getVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IndexVector_insert" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixDynSize const *)arg1)->getVal(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + temp3 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val3); + arg3 = &temp3; + result = std_vector_Sl_std_ptrdiff_t_Sg__insert__SWIG_0(arg1,arg2,(::ptrdiff_t const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< ::ptrdiff_t >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10892,47 +11139,54 @@ int _wrap_MatrixDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_MatrixDynSize_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; +int _wrap_IndexVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + SwigValueWrapper< std::vector< ::ptrdiff_t >::iterator > arg2 ; + std::vector< ::ptrdiff_t >::size_type arg3 ; + std::vector< ::ptrdiff_t >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; size_t val3 ; int ecode3 = 0 ; - double val4 ; + std::vector< ::ptrdiff_t >::value_type temp4 ; + ptrdiff_t val4 ; int ecode4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("MatrixDynSize_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("IndexVector_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_setVal" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_insert" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_insert" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "IndexVector_insert" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::iterator""'"); + } } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_setVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IndexVector_insert" "', argument " "3"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); + arg3 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "MatrixDynSize_setVal" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IndexVector_insert" "', argument " "4"" of type '" "std::vector< ::ptrdiff_t >::value_type""'"); } - arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + temp4 = static_cast< std::vector< ::ptrdiff_t >::value_type >(val4); + arg4 = &temp4; + std_vector_Sl_std_ptrdiff_t_Sg__insert__SWIG_1(arg1,arg2,arg3,(::ptrdiff_t const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10940,23 +11194,84 @@ int _wrap_MatrixDynSize_setVal(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_MatrixDynSize_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_IndexVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_IndexVector_insert__SWIG_0(resc,resv,argc,argv); + } + } + } + } + if (argc == 4) { + int _v; + int res = swig::asptr(argv[0], (std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[3], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_IndexVector_insert__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'IndexVector_insert'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::ptrdiff_t >::insert(std::vector< ::ptrdiff_t >::iterator,std::vector< ::ptrdiff_t >::value_type const &)\n" + " std::vector< std::ptrdiff_t >::insert(std::vector< ::ptrdiff_t >::iterator,std::vector< ::ptrdiff_t >::size_type,std::vector< ::ptrdiff_t >::value_type const &)\n"); + return 1; +} + + +int _wrap_IndexVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; + std::vector< ::ptrdiff_t >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("MatrixDynSize_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_rows" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_reserve" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = ((iDynTree::MatrixDynSize const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexVector_reserve" "', argument " "2"" of type '" "std::vector< ::ptrdiff_t >::size_type""'"); + } + arg2 = static_cast< std::vector< ::ptrdiff_t >::size_type >(val2); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -10964,22 +11279,22 @@ int _wrap_MatrixDynSize_rows(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_MatrixDynSize_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_IndexVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; + std::vector< ::ptrdiff_t >::size_type result; - if (!SWIG_check_num_args("MatrixDynSize_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexVector_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_cols" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexVector_capacity" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = ((iDynTree::MatrixDynSize const *)arg1)->cols(); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + result = ((std::vector< std::ptrdiff_t > const *)arg1)->capacity(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -10988,23 +11303,26 @@ int _wrap_MatrixDynSize_cols(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_MatrixDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_delete_IndexVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::ptrdiff_t > *arg1 = (std::vector< std::ptrdiff_t > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("MatrixDynSize_data",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_IndexVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_data" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_IndexVector" "', argument " "1"" of type '" "std::vector< std::ptrdiff_t > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< std::ptrdiff_t > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11012,22 +11330,29 @@ int _wrap_MatrixDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_MatrixDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_BerdySensors_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor >::value_type result; - if (!SWIG_check_num_args("MatrixDynSize_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_zero" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_pop" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + try { + result = std_vector_Sl_iDynTree_BerdySensor_Sg__pop(arg1); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::value_type(static_cast< const std::vector< iDynTree::BerdySensor >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdySensor, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11035,38 +11360,37 @@ int _wrap_MatrixDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_MatrixDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdySensors_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor >::value_type result; - if (!SWIG_check_num_args("MatrixDynSize_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_resize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_brace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_resize" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_brace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::difference_type""'"); } - arg3 = static_cast< std::size_t >(val3); - (arg1)->resize(arg2,arg3); - _out = (mxArray*)0; + arg2 = static_cast< std::vector< iDynTree::BerdySensor >::difference_type >(val2); + try { + result = std_vector_Sl_iDynTree_BerdySensor_Sg__brace(arg1,arg2); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::value_type(static_cast< const std::vector< iDynTree::BerdySensor >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdySensor, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11074,29 +11398,49 @@ int _wrap_MatrixDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_MatrixDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - size_t arg2 ; +int _wrap_BerdySensors_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::value_type arg2 ; + std::vector< iDynTree::BerdySensor >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("MatrixDynSize_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_reserve" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_reserve" "', argument " "2"" of type '" "size_t""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + { + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + } else { + arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2)); + } + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdySensors_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::difference_type""'"); } - arg2 = static_cast< size_t >(val2); - (arg1)->reserve(arg2); + arg3 = static_cast< std::vector< iDynTree::BerdySensor >::difference_type >(val3); + try { + std_vector_Sl_iDynTree_BerdySensor_Sg__setbrace(arg1,arg2,arg3); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -11105,23 +11449,36 @@ int _wrap_MatrixDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_MatrixDynSize_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_BerdySensors_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::value_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - size_t result; - if (!SWIG_check_num_args("MatrixDynSize_capacity",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_capacity" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_append" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = ((iDynTree::MatrixDynSize const *)arg1)->capacity(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + { + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type""'"); + } else { + arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2)); + } + } + std_vector_Sl_iDynTree_BerdySensor_Sg__append(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11129,22 +11486,16 @@ int _wrap_MatrixDynSize_capacity(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_MatrixDynSize_shrink_to_fit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_BerdySensors__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + std::vector< iDynTree::BerdySensor > *result = 0 ; - if (!SWIG_check_num_args("MatrixDynSize_shrink_to_fit",argc,1,1,0)) { + if (!SWIG_check_num_args("new_BerdySensors",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_shrink_to_fit" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - (arg1)->shrink_to_fit(); - _out = (mxArray*)0; + (void)argv; + result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11152,61 +11503,54 @@ int _wrap_MatrixDynSize_shrink_to_fit(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_MatrixDynSize_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; +int _wrap_new_BerdySensors__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = 0 ; + int res1 = SWIG_OLDOBJ ; mxArray * _out; + std::vector< iDynTree::BerdySensor > *result = 0 ; - if (!SWIG_check_num_args("MatrixDynSize_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("new_BerdySensors",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSize_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + { + std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > > *ptr = (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > > *)0; + res1 = swig::asptr(argv[0], &ptr); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const &""'"); + } + arg1 = ptr; } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixDynSize const *)arg1)->fillRowMajorBuffer(arg2); - _out = (mxArray*)0; + result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >((std::vector< iDynTree::BerdySensor > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res1)) delete arg1; return 0; fail: + if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_MatrixDynSize_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_BerdySensors_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("MatrixDynSize_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSize_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_empty" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixDynSize const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (bool)((std::vector< iDynTree::BerdySensor > const *)arg1)->empty(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11214,23 +11558,23 @@ int _wrap_MatrixDynSize_fillColMajorBuffer(int resc, mxArray *resv[], int argc, } -int _wrap_MatrixDynSize_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_BerdySensors_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + std::vector< iDynTree::BerdySensor >::size_type result; - if (!SWIG_check_num_args("MatrixDynSize_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_toString" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_size" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = ((iDynTree::MatrixDynSize const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11238,23 +11582,33 @@ int _wrap_MatrixDynSize_toString(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_MatrixDynSize_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_BerdySensors_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("MatrixDynSize_display",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_swap",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_display" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_swap" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = ((iDynTree::MatrixDynSize const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor > &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor > &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp2); + (arg1)->swap(*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11262,23 +11616,24 @@ int _wrap_MatrixDynSize_display(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_MatrixDynSize_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; +int _wrap_BerdySensors_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - mxArray *result = 0 ; + std::vector< iDynTree::BerdySensor >::iterator result; - if (!SWIG_check_num_args("MatrixDynSize_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_begin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - result = (mxArray *)iDynTree_MatrixDynSize_toMatlab((iDynTree::MatrixDynSize const *)arg1); - _out = result; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (arg1)->begin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11286,24 +11641,24 @@ int _wrap_MatrixDynSize_toMatlab(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_MatrixDynSize_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_BerdySensors_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor >::iterator result; - if (!SWIG_check_num_args("MatrixDynSize_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_end" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); - arg2 = argv[1]; - iDynTree_MatrixDynSize_fromMatlab(arg1,arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (arg1)->end(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11311,16 +11666,24 @@ int _wrap_MatrixDynSize_fromMatlab(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_SparseMatrixRowMajor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_BerdySensors_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; + std::vector< iDynTree::BerdySensor >::reverse_iterator result; - if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,0,0,0)) { + if (!SWIG_check_num_args("BerdySensors_rbegin",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (arg1)->rbegin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11328,31 +11691,24 @@ int _wrap_new_SparseMatrixRowMajor__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_SparseMatrixRowMajor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_BerdySensors_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; + std::vector< iDynTree::BerdySensor >::reverse_iterator result; - if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_rend",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixRowMajor" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixRowMajor" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_rend" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (arg1)->rend(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11360,42 +11716,22 @@ int _wrap_new_SparseMatrixRowMajor__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_SparseMatrixRowMajor__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - iDynTree::VectorDynSize *arg3 = 0 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; +int _wrap_BerdySensors_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; - if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_clear",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixRowMajor" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixRowMajor" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SparseMatrixRowMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SparseMatrixRowMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_clear" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(arg1,arg2,(iDynTree::VectorDynSize const &)*arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + (arg1)->clear(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11403,77 +11739,47 @@ int _wrap_new_SparseMatrixRowMajor__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_new_SparseMatrixRowMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SparseMatrixRowMajor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 2) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_SparseMatrixRowMajor__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_BerdySensors_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + SwigValueWrapper< std::allocator< iDynTree::BerdySensor > > result; + + if (!SWIG_check_num_args("BerdySensors_get_allocator",argc,1,1,0)) { + SWIG_fail; } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SparseMatrixRowMajor__SWIG_2(resc,resv,argc,argv); - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SparseMatrixRowMajor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix()\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix(std::size_t,std::size_t)\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdySensor >::allocator_type(static_cast< const std::vector< iDynTree::BerdySensor >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__BerdySensor_t, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_delete_SparseMatrixRowMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_BerdySensors__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor >::size_type arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor > *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_SparseMatrixRowMajor",argc,1,1,0)) { + if (!SWIG_check_num_args("new_BerdySensors",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SparseMatrixRowMajor" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + } + arg1 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val1); + result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11481,23 +11787,22 @@ int _wrap_delete_SparseMatrixRowMajor(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SparseMatrixRowMajor_numberOfNonZeros(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; +int _wrap_BerdySensors_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_numberOfNonZeros",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_numberOfNonZeros" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->numberOfNonZeros(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + (arg1)->pop_back(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11505,37 +11810,29 @@ int _wrap_SparseMatrixRowMajor_numberOfNonZeros(int resc, mxArray *resv[], int a } -int _wrap_SparseMatrixRowMajor_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdySensors_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixRowMajor_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - (arg1)->resize(arg2,arg3); + arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -11544,49 +11841,91 @@ int _wrap_SparseMatrixRowMajor_resize__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_SparseMatrixRowMajor_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - iDynTree::VectorDynSize *arg4 = 0 ; +int _wrap_BerdySensors_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - void *argp4 ; - int res4 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; mxArray * _out; + std::vector< iDynTree::BerdySensor >::iterator result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_resize",argc,4,4,0)) { + if (!SWIG_check_num_args("BerdySensors_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SparseMatrixRowMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + result = std_vector_Sl_iDynTree_BerdySensor_Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_BerdySensors_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::iterator arg2 ; + std::vector< iDynTree::BerdySensor >::iterator arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + swig::MatlabSwigIterator *iter3 = 0 ; + int res3 ; + mxArray * _out; + std::vector< iDynTree::BerdySensor >::iterator result; + + if (!SWIG_check_num_args("BerdySensors_erase",argc,3,3,0)) { + SWIG_fail; } - arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); - (arg1)->resize(arg2,arg3,(iDynTree::VectorDynSize const &)*arg4); - _out = (mxArray*)0; + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } + } + res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res3) || !iter3) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + if (iter_t) { + arg3 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } + } + result = std_vector_Sl_iDynTree_BerdySensor_Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11594,87 +11933,75 @@ int _wrap_SparseMatrixRowMajor_resize__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_SparseMatrixRowMajor_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_BerdySensors_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixRowMajor_resize__SWIG_0(resc,resv,argc,argv); - } + return _wrap_BerdySensors_erase__SWIG_0(resc,resv,argc,argv); } } } - if (argc == 4) { + if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SparseMatrixRowMajor_resize__SWIG_1(resc,resv,argc,argv); - } + return _wrap_BerdySensors_erase__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_erase'." " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::resize(std::size_t,std::size_t)\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::resize(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); + " std::vector< iDynTree::BerdySensor >::erase(std::vector< iDynTree::BerdySensor >::iterator)\n" + " std::vector< iDynTree::BerdySensor >::erase(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::iterator)\n"); return 1; } -int _wrap_SparseMatrixRowMajor_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_new_BerdySensors__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor >::size_type arg1 ; + std::vector< iDynTree::BerdySensor >::value_type *arg2 = 0 ; + size_t val1 ; + int ecode1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor > *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixRowMajor_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("new_BerdySensors",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_reserve" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_reserve" "', argument " "2"" of type '" "std::size_t""'"); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - (arg1)->reserve(arg2); - _out = (mxArray*)0; + arg1 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_BerdySensors" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdySensors" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2); + result = (std::vector< iDynTree::BerdySensor > *)new std::vector< iDynTree::BerdySensor >(arg1,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11682,55 +12009,80 @@ int _wrap_SparseMatrixRowMajor_reserve(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SparseMatrixRowMajor_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("SparseMatrixRowMajor_zero",argc,1,1,0)) { - SWIG_fail; +int _wrap_new_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_BerdySensors__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_zero" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_BerdySensors__SWIG_2(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 1) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_BerdySensors__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_BerdySensors__SWIG_3(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_BerdySensors'." + " Possible C/C++ prototypes are:\n" + " std::vector< iDynTree::BerdySensor >::vector()\n" + " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor > const &)\n" + " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor >::size_type)\n" + " std::vector< iDynTree::BerdySensor >::vector(std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); return 1; } -int _wrap_SparseMatrixRowMajor_setFromConstTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - iDynTree::Triplets *arg2 = 0 ; +int _wrap_BerdySensors_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixRowMajor_setFromConstTriplets",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdySensors_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); } - arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); - (arg1)->setFromConstTriplets((iDynTree::Triplets const &)*arg2); + arg2 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp2); + (arg1)->push_back((std::vector< iDynTree::BerdySensor >::value_type const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -11739,33 +12091,23 @@ int _wrap_SparseMatrixRowMajor_setFromConstTriplets(int resc, mxArray *resv[], i } -int _wrap_SparseMatrixRowMajor_setFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - iDynTree::Triplets *arg2 = 0 ; +int _wrap_BerdySensors_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdySensor >::value_type *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixRowMajor_setFromTriplets",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_front" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); - (arg1)->setFromTriplets(*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (std::vector< iDynTree::BerdySensor >::value_type *) &((std::vector< iDynTree::BerdySensor > const *)arg1)->front(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdySensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11773,42 +12115,23 @@ int _wrap_SparseMatrixRowMajor_setFromTriplets(int resc, mxArray *resv[], int ar } -int _wrap_SparseMatrixRowMajor_sparseMatrixFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - iDynTree::Triplets *arg3 = 0 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; +int _wrap_BerdySensors_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::RowMajor > result; + std::vector< iDynTree::BerdySensor >::value_type *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixRowMajor_sparseMatrixFromTriplets",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_back",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Triplets, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - arg3 = reinterpret_cast< iDynTree::Triplets * >(argp3); - result = iDynTree::SparseMatrix< iDynTree::RowMajor >::SWIGTEMPLATEDISAMBIGUATOR sparseMatrixFromTriplets(arg1,arg2,(iDynTree::Triplets const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::SparseMatrix< iDynTree::RowMajor >(static_cast< const iDynTree::SparseMatrix< iDynTree::RowMajor >& >(result))), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = (std::vector< iDynTree::BerdySensor >::value_type *) &((std::vector< iDynTree::BerdySensor > const *)arg1)->back(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdySensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11816,39 +12139,41 @@ int _wrap_SparseMatrixRowMajor_sparseMatrixFromTriplets(int resc, mxArray *resv[ } -int _wrap_SparseMatrixRowMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdySensors_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::size_type arg2 ; + std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_assign" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_assign" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); + (arg1)->assign(arg2,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11856,39 +12181,41 @@ int _wrap_SparseMatrixRowMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixRowMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdySensors_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::size_type arg2 ; + std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixRowMajor_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); + (arg1)->resize(arg2,(std::vector< iDynTree::BerdySensor >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11896,11 +12223,10 @@ int _wrap_SparseMatrixRowMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixRowMajor_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_BerdySensors_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -11908,20 +12234,13 @@ int _wrap_SparseMatrixRowMajor_paren(int resc, mxArray *resv[], int argc, mxArra _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixRowMajor_paren__SWIG_0(resc,resv,argc,argv); - } + return _wrap_BerdySensors_resize__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -11929,58 +12248,67 @@ int _wrap_SparseMatrixRowMajor_paren(int resc, mxArray *resv[], int argc, mxArra _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_SparseMatrixRowMajor_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_BerdySensors_resize__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::operator ()(std::size_t,std::size_t) const\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::operator ()(std::size_t,std::size_t)\n"); + " std::vector< iDynTree::BerdySensor >::resize(std::vector< iDynTree::BerdySensor >::size_type)\n" + " std::vector< iDynTree::BerdySensor >::resize(std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); return 1; } -int _wrap_SparseMatrixRowMajor_getValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdySensors_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::iterator arg2 ; + std::vector< iDynTree::BerdySensor >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - double result; + std::vector< iDynTree::BerdySensor >::iterator result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_getValue",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdySensors_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->getValue(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } + } + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp3); + result = std_vector_Sl_iDynTree_BerdySensor_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::BerdySensor const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdySensor >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -11988,45 +12316,54 @@ int _wrap_SparseMatrixRowMajor_getValue(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixRowMajor_setValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; +int _wrap_BerdySensors_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::iterator arg2 ; + std::vector< iDynTree::BerdySensor >::size_type arg3 ; + std::vector< iDynTree::BerdySensor >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; size_t val3 ; int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixRowMajor_setValue",argc,4,4,0)) { + if (!SWIG_check_num_args("BerdySensors_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdySensors_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::iterator""'"); + } } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdySensors_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); } - arg4 = static_cast< double >(val4); - (arg1)->setValue(arg2,arg3,arg4); + arg3 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__BerdySensor, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "BerdySensors_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdySensors_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdySensor >::value_type const &""'"); + } + arg4 = reinterpret_cast< std::vector< iDynTree::BerdySensor >::value_type * >(argp4); + std_vector_Sl_iDynTree_BerdySensor_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::BerdySensor const &)*arg4); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -12035,47 +12372,82 @@ int _wrap_SparseMatrixRowMajor_setValue(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixRowMajor_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("SparseMatrixRowMajor_rows",argc,1,1,0)) { - SWIG_fail; +int _wrap_BerdySensors_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdySensors_insert__SWIG_0(resc,resv,argc,argv); + } + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_rows" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + if (argc == 4) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__BerdySensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdySensors_insert__SWIG_1(resc,resv,argc,argv); + } + } + } + } } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdySensors_insert'." + " Possible C/C++ prototypes are:\n" + " std::vector< iDynTree::BerdySensor >::insert(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::value_type const &)\n" + " std::vector< iDynTree::BerdySensor >::insert(std::vector< iDynTree::BerdySensor >::iterator,std::vector< iDynTree::BerdySensor >::size_type,std::vector< iDynTree::BerdySensor >::value_type const &)\n"); return 1; } -int _wrap_SparseMatrixRowMajor_columns(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; +int _wrap_BerdySensors_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; + std::vector< iDynTree::BerdySensor >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_columns",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdySensors_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_columns" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->columns(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdySensors_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::BerdySensor >::size_type""'"); + } + arg2 = static_cast< std::vector< iDynTree::BerdySensor >::size_type >(val2); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12083,31 +12455,23 @@ int _wrap_SparseMatrixRowMajor_columns(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SparseMatrixRowMajor_description__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - bool arg2 ; +int _wrap_BerdySensors_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - bool val2 ; - int ecode2 = 0 ; mxArray * _out; - std::string result; + std::vector< iDynTree::BerdySensor >::size_type result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_description",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdySensors_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdySensors_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - ecode2 = SWIG_AsVal_bool(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_description" "', argument " "2"" of type '" "bool""'"); - } - arg2 = static_cast< bool >(val2); - result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->description(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + result = ((std::vector< iDynTree::BerdySensor > const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12115,23 +12479,26 @@ int _wrap_SparseMatrixRowMajor_description__SWIG_0(int resc, mxArray *resv[], in } -int _wrap_SparseMatrixRowMajor_description__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; +int _wrap_delete_BerdySensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdySensor > *arg1 = (std::vector< iDynTree::BerdySensor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_description",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_BerdySensors",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_BerdySensors" "', argument " "1"" of type '" "std::vector< iDynTree::BerdySensor > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->description(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdySensor > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12139,57 +12506,29 @@ int _wrap_SparseMatrixRowMajor_description__SWIG_1(int resc, mxArray *resv[], in } -int _wrap_SparseMatrixRowMajor_description(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SparseMatrixRowMajor_description__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_bool(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixRowMajor_description__SWIG_0(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_description'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::description(bool) const\n" - " iDynTree::SparseMatrix< iDynTree::RowMajor >::description() const\n"); - return 1; -} - - -int _wrap_SparseMatrixRowMajor_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - mxArray *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_toMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_pop" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__toMatlab((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1); - _out = result; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + try { + result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__pop(arg1); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::value_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12197,23 +12536,37 @@ int _wrap_SparseMatrixRowMajor_toMatlab(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixRowMajor_toMatlabDense(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - mxArray *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type result; - if (!SWIG_check_num_args("SparseMatrixRowMajor_toMatlabDense",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_toMatlabDense" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_brace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__toMatlabDense((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1); - _out = result; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_brace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::difference_type""'"); + } + arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::difference_type >(val2); + try { + result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__brace(arg1,arg2); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::value_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::value_type& >(result))), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12221,23 +12574,49 @@ int _wrap_SparseMatrixRowMajor_toMatlabDense(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixRowMajor_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_BerdyDynamicVariables_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixRowMajor_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_fromMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); - arg2 = argv[1]; - iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__fromMatlab(arg1,arg2); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + { + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + } else { + arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2)); + } + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdyDynamicVariables_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::difference_type""'"); + } + arg3 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::difference_type >(val3); + try { + std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__setbrace(arg1,arg2,arg3); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -12246,16 +12625,36 @@ int _wrap_SparseMatrixRowMajor_fromMatlab(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SparseMatrixColMajor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_BerdyDynamicVariables_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; - if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,0,0,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_append",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_append" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + { + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_append" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type""'"); + } else { + arg2 = *(reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2)); + } + } + std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__append(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12263,31 +12662,16 @@ int _wrap_new_SparseMatrixColMajor__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_SparseMatrixColMajor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_new_BerdyDynamicVariables__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; - if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,2,2,0)) { + if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,0,0,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixColMajor" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixColMajor" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); + (void)argv; + result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12295,120 +12679,54 @@ int _wrap_new_SparseMatrixColMajor__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_SparseMatrixColMajor__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - iDynTree::VectorDynSize *arg3 = 0 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; +int _wrap_new_BerdyDynamicVariables__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = 0 ; + int res1 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; - if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,3,3,0)) { + if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixColMajor" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixColMajor" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SparseMatrixColMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SparseMatrixColMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + { + std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > > *ptr = (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > > *)0; + res1 = swig::asptr(argv[0], &ptr); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const &""'"); + } + arg1 = ptr; } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(arg1,arg2,(iDynTree::VectorDynSize const &)*arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); + result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >((std::vector< iDynTree::BerdyDynamicVariable > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res1)) delete arg1; return 0; fail: + if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_new_SparseMatrixColMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SparseMatrixColMajor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 2) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_SparseMatrixColMajor__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SparseMatrixColMajor__SWIG_2(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SparseMatrixColMajor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix()\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix(std::size_t,std::size_t)\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); - return 1; -} - - -int _wrap_delete_SparseMatrixColMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_SparseMatrixColMajor",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_empty",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SparseMatrixColMajor" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_empty" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (bool)((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->empty(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12416,22 +12734,22 @@ int _wrap_delete_SparseMatrixColMajor(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SparseMatrixColMajor_numberOfNonZeros(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; + std::vector< iDynTree::BerdyDynamicVariable >::size_type result; - if (!SWIG_check_num_args("SparseMatrixColMajor_numberOfNonZeros",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_numberOfNonZeros" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_size" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->numberOfNonZeros(); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->size(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -12440,37 +12758,32 @@ int _wrap_SparseMatrixColMajor_numberOfNonZeros(int resc, mxArray *resv[], int a } -int _wrap_SparseMatrixColMajor_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdyDynamicVariables_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixColMajor_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_swap",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_swap" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - (arg1)->resize(arg2,arg3); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_swap" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp2); + (arg1)->swap(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -12479,49 +12792,24 @@ int _wrap_SparseMatrixColMajor_resize__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_SparseMatrixColMajor_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - iDynTree::VectorDynSize *arg4 = 0 ; +int _wrap_BerdyDynamicVariables_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - void *argp4 ; - int res4 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_resize",argc,4,4,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SparseMatrixColMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_begin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); - (arg1)->resize(arg2,arg3,(iDynTree::VectorDynSize const &)*arg4); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (arg1)->begin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12529,87 +12817,24 @@ int _wrap_SparseMatrixColMajor_resize__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_SparseMatrixColMajor_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixColMajor_resize__SWIG_0(resc,resv,argc,argv); - } - } - } - } - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SparseMatrixColMajor_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::resize(std::size_t,std::size_t)\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::resize(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); - return 1; -} - - -int _wrap_SparseMatrixColMajor_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; +int _wrap_BerdyDynamicVariables_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_reserve" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_end" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_reserve" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->reserve(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (arg1)->end(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12617,22 +12842,24 @@ int _wrap_SparseMatrixColMajor_reserve(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SparseMatrixColMajor_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_zero" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (arg1)->rbegin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12640,33 +12867,24 @@ int _wrap_SparseMatrixColMajor_zero(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SparseMatrixColMajor_setFromConstTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - iDynTree::Triplets *arg2 = 0 ; +int _wrap_BerdyDynamicVariables_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_setFromConstTriplets",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_rend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_rend" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); - (arg1)->setFromConstTriplets((iDynTree::Triplets const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (arg1)->rend(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12674,32 +12892,21 @@ int _wrap_SparseMatrixColMajor_setFromConstTriplets(int resc, mxArray *resv[], i } -int _wrap_SparseMatrixColMajor_setFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - iDynTree::Triplets *arg2 = 0 ; +int _wrap_BerdyDynamicVariables_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixColMajor_setFromTriplets",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_clear",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_clear" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); - (arg1)->setFromTriplets(*arg2); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + (arg1)->clear(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -12708,82 +12915,23 @@ int _wrap_SparseMatrixColMajor_setFromTriplets(int resc, mxArray *resv[], int ar } -int _wrap_SparseMatrixColMajor_sparseMatrixFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - std::size_t arg2 ; - iDynTree::Triplets *arg3 = 0 ; - size_t val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; - mxArray * _out; - iDynTree::SparseMatrix< iDynTree::ColumnMajor > result; - - if (!SWIG_check_num_args("SparseMatrixColMajor_sparseMatrixFromTriplets",argc,3,3,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Triplets, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); - } - arg3 = reinterpret_cast< iDynTree::Triplets * >(argp3); - result = iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SWIGTEMPLATEDISAMBIGUATOR sparseMatrixFromTriplets(arg1,arg2,(iDynTree::Triplets const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(static_cast< const iDynTree::SparseMatrix< iDynTree::ColumnMajor >& >(result))), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SparseMatrixColMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdyDynamicVariables_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - double result; + SwigValueWrapper< std::allocator< iDynTree::BerdyDynamicVariable > > result; - if (!SWIG_check_num_args("SparseMatrixColMajor_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_get_allocator",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::BerdyDynamicVariable >::allocator_type(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__BerdyDynamicVariable_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12791,39 +12939,23 @@ int _wrap_SparseMatrixColMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixColMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; +int _wrap_new_BerdyDynamicVariables__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - double *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixColMajor_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); } - arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val1); + result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12831,91 +12963,22 @@ int _wrap_SparseMatrixColMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixColMajor_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixColMajor_paren__SWIG_0(resc,resv,argc,argv); - } - } - } - } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SparseMatrixColMajor_paren__SWIG_1(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_paren'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::operator ()(std::size_t,std::size_t) const\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::operator ()(std::size_t,std::size_t)\n"); - return 1; -} - - -int _wrap_SparseMatrixColMajor_getValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; +int _wrap_BerdyDynamicVariables_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("SparseMatrixColMajor_getValue",argc,3,3,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_getValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_getValue" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_getValue" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->getValue(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + (arg1)->pop_back(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12923,45 +12986,29 @@ int _wrap_SparseMatrixColMajor_getValue(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixColMajor_setValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; +int _wrap_BerdyDynamicVariables_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SparseMatrixColMajor_setValue",argc,4,4,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_setValue" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_setValue" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "SparseMatrixColMajor_setValue" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); } - arg4 = static_cast< double >(val4); - (arg1)->setValue(arg2,arg3,arg4); + arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -12970,23 +13017,38 @@ int _wrap_SparseMatrixColMajor_setValue(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixColMajor_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; mxArray * _out; - std::size_t result; + std::vector< iDynTree::BerdyDynamicVariable >::iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_rows" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } + } + result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -12994,23 +13056,52 @@ int _wrap_SparseMatrixColMajor_rows(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SparseMatrixColMajor_columns(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::iterator arg3 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + swig::MatlabSwigIterator *iter3 = 0 ; + int res3 ; mxArray * _out; - std::size_t result; + std::vector< iDynTree::BerdyDynamicVariable >::iterator result; - if (!SWIG_check_num_args("SparseMatrixColMajor_columns",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_erase",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_columns" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_erase" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->columns(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } + } + res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res3) || !iter3) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + if (iter_t) { + arg3 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_erase" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } + } + result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13018,55 +13109,75 @@ int _wrap_SparseMatrixColMajor_columns(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SparseMatrixColMajor_description__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - bool arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - bool val2 ; - int ecode2 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("SparseMatrixColMajor_description",argc,2,2,0)) { - SWIG_fail; +int _wrap_BerdyDynamicVariables_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_BerdyDynamicVariables_erase__SWIG_0(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_BerdyDynamicVariables_erase__SWIG_1(resc,resv,argc,argv); + } + } + } } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - ecode2 = SWIG_AsVal_bool(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_description" "', argument " "2"" of type '" "bool""'"); - } - arg2 = static_cast< bool >(val2); - result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->description(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_erase'." + " Possible C/C++ prototypes are:\n" + " std::vector< iDynTree::BerdyDynamicVariable >::erase(std::vector< iDynTree::BerdyDynamicVariable >::iterator)\n" + " std::vector< iDynTree::BerdyDynamicVariable >::erase(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::iterator)\n"); return 1; } -int _wrap_SparseMatrixColMajor_description__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_BerdyDynamicVariables__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg1 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg2 = 0 ; + size_t val1 ; + int ecode1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::string result; + std::vector< iDynTree::BerdyDynamicVariable > *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixColMajor_description",argc,1,1,0)) { + if (!SWIG_check_num_args("new_BerdyDynamicVariables",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + } + arg1 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_BerdyDynamicVariables" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->description(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_BerdyDynamicVariables" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2); + result = (std::vector< iDynTree::BerdyDynamicVariable > *)new std::vector< iDynTree::BerdyDynamicVariable >(arg1,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13074,57 +13185,81 @@ int _wrap_SparseMatrixColMajor_description__SWIG_1(int resc, mxArray *resv[], in } -int _wrap_SparseMatrixColMajor_description(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_BerdyDynamicVariables__SWIG_0(resc,resv,argc,argv); + } if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_BerdyDynamicVariables__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_SparseMatrixColMajor_description__SWIG_1(resc,resv,argc,argv); + return _wrap_new_BerdyDynamicVariables__SWIG_1(resc,resv,argc,argv); } } if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - { - int res = SWIG_AsVal_bool(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_SparseMatrixColMajor_description__SWIG_0(resc,resv,argc,argv); + return _wrap_new_BerdyDynamicVariables__SWIG_3(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_description'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_BerdyDynamicVariables'." " Possible C/C++ prototypes are:\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::description(bool) const\n" - " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::description() const\n"); + " std::vector< iDynTree::BerdyDynamicVariable >::vector()\n" + " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable > const &)\n" + " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable >::size_type)\n" + " std::vector< iDynTree::BerdyDynamicVariable >::vector(std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); return 1; } -int _wrap_SparseMatrixColMajor_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - mxArray *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixColMajor_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_toMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__toMatlab((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1); - _out = result; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyDynamicVariables_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp2); + (arg1)->push_back((std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13132,23 +13267,23 @@ int _wrap_SparseMatrixColMajor_toMatlab(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SparseMatrixColMajor_toMatlabDense(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; +int _wrap_BerdyDynamicVariables_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - mxArray *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixColMajor_toMatlabDense",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_toMatlabDense" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_front" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__toMatlabDense((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1); - _out = result; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (std::vector< iDynTree::BerdyDynamicVariable >::value_type *) &((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->front(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13156,65 +13291,23 @@ int _wrap_SparseMatrixColMajor_toMatlabDense(int resc, mxArray *resv[], int argc } -int _wrap_SparseMatrixColMajor_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_BerdyDynamicVariables_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *result = 0 ; - if (!SWIG_check_num_args("SparseMatrixColMajor_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_fromMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_back" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); - arg2 = argv[1]; - iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_VectorDynSize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::VectorDynSize *result = 0 ; - - if (!SWIG_check_num_args("new_VectorDynSize",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_VectorDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; - mxArray * _out; - iDynTree::VectorDynSize *result = 0 ; - - if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = (std::vector< iDynTree::BerdyDynamicVariable >::value_type *) &((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->back(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13222,31 +13315,41 @@ int _wrap_new_VectorDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_VectorDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - std::size_t arg2 ; +int _wrap_BerdyDynamicVariables_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::VectorDynSize *result = 0 ; - if (!SWIG_check_num_args("new_VectorDynSize",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_assign" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< double * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_VectorDynSize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_assign" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); + arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_assign" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); + (arg1)->assign(arg2,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13254,56 +13357,41 @@ int _wrap_new_VectorDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_VectorDynSize__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = 0 ; - void *argp1 ; +int _wrap_BerdyDynamicVariables_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::VectorDynSize *result = 0 ; - if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_resize" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize((iDynTree::VectorDynSize const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_VectorDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::VectorDynSize *result = 0 ; - - if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { - SWIG_fail; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_resize" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); + } + arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); - } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_resize" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); } - result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); + arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); + (arg1)->resize(arg2,(std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13311,42 +13399,24 @@ int _wrap_new_VectorDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_VectorDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_VectorDynSize__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_VectorDynSize__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 1) { +int _wrap_BerdyDynamicVariables_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_VectorDynSize__SWIG_4(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_VectorDynSize__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_BerdyDynamicVariables_resize__SWIG_0(resc,resv,argc,argv); + } } } - if (argc == 2) { + if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); _v = SWIG_CheckState(res); if (_v) { { @@ -13354,74 +13424,67 @@ int _wrap_new_VectorDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[] _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_VectorDynSize__SWIG_2(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdyDynamicVariables_resize__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_VectorDynSize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorDynSize::VectorDynSize()\n" - " iDynTree::VectorDynSize::VectorDynSize(std::size_t)\n" - " iDynTree::VectorDynSize::VectorDynSize(double const *,std::size_t const)\n" - " iDynTree::VectorDynSize::VectorDynSize(iDynTree::VectorDynSize const &)\n" - " iDynTree::VectorDynSize::VectorDynSize(iDynTree::Span< double const,-1 >)\n"); + " std::vector< iDynTree::BerdyDynamicVariable >::resize(std::vector< iDynTree::BerdyDynamicVariable >::size_type)\n" + " std::vector< iDynTree::BerdyDynamicVariable >::resize(std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); return 1; } -int _wrap_delete_VectorDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_BerdyDynamicVariables_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; + std::vector< iDynTree::BerdyDynamicVariable >::iterator result; - int is_owned; - if (!SWIG_check_num_args("delete_VectorDynSize",argc,1,1,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_insert",argc,3,3,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - double result; - - if (!SWIG_check_num_args("VectorDynSize_paren",argc,2,2,0)) { - SWIG_fail; + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_paren" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorDynSize const *)arg1)->operator ()(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg3 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp3); + result = std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__insert__SWIG_0(arg1,arg2,(iDynTree::BerdyDynamicVariable const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::BerdyDynamicVariable >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13429,31 +13492,55 @@ int _wrap_VectorDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_VectorDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; +int _wrap_BerdyDynamicVariables_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::iterator arg2 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg3 ; + std::vector< iDynTree::BerdyDynamicVariable >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + size_t val3 ; + int ecode3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_paren" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_insert" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "BerdyDynamicVariables_insert" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::iterator""'"); + } + } + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "BerdyDynamicVariables_insert" "', argument " "3"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg3 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "BerdyDynamicVariables_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyDynamicVariables_insert" "', argument " "4"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::value_type const &""'"); + } + arg4 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable >::value_type * >(argp4); + std_vector_Sl_iDynTree_BerdyDynamicVariable_Sg__insert__SWIG_1(arg1,arg2,arg3,(iDynTree::BerdyDynamicVariable const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13461,71 +13548,82 @@ int _wrap_VectorDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_VectorDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_BerdyDynamicVariables_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_VectorDynSize_paren__SWIG_0(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdyDynamicVariables_insert__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 4) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_VectorDynSize_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__BerdyDynamicVariable, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdyDynamicVariables_insert__SWIG_1(resc,resv,argc,argv); + } + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyDynamicVariables_insert'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorDynSize::operator ()(std::size_t const) const\n" - " iDynTree::VectorDynSize::operator ()(std::size_t const)\n"); + " std::vector< iDynTree::BerdyDynamicVariable >::insert(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n" + " std::vector< iDynTree::BerdyDynamicVariable >::insert(std::vector< iDynTree::BerdyDynamicVariable >::iterator,std::vector< iDynTree::BerdyDynamicVariable >::size_type,std::vector< iDynTree::BerdyDynamicVariable >::value_type const &)\n"); return 1; } -int _wrap_VectorDynSize_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; +int _wrap_BerdyDynamicVariables_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("VectorDynSize_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_brace" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "BerdyDynamicVariables_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::BerdyDynamicVariable >::size_type""'"); } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorDynSize const *)arg1)->operator [](arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg2 = static_cast< std::vector< iDynTree::BerdyDynamicVariable >::size_type >(val2); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13533,31 +13631,23 @@ int _wrap_VectorDynSize_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_VectorDynSize_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; +int _wrap_BerdyDynamicVariables_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double *result = 0 ; + std::vector< iDynTree::BerdyDynamicVariable >::size_type result; - if (!SWIG_check_num_args("VectorDynSize_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("BerdyDynamicVariables_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_brace" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyDynamicVariables_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_brace" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + result = ((std::vector< iDynTree::BerdyDynamicVariable > const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13565,71 +13655,26 @@ int _wrap_VectorDynSize_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_VectorDynSize_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_VectorDynSize_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_VectorDynSize_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorDynSize::operator [](std::size_t const) const\n" - " iDynTree::VectorDynSize::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_VectorDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; +int _wrap_delete_BerdyDynamicVariables(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::BerdyDynamicVariable > *arg1 = (std::vector< iDynTree::BerdyDynamicVariable > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("VectorDynSize_getVal",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_BerdyDynamicVariables",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_getVal" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_BerdyDynamicVariables" "', argument " "1"" of type '" "std::vector< iDynTree::BerdyDynamicVariable > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorDynSize const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::BerdyDynamicVariable > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13637,87 +13682,126 @@ int _wrap_VectorDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_VectorDynSize_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - std::size_t arg2 ; - double arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - bool result; +int _wrap_reportInfo(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + char *arg1 = (char *) 0 ; + char *arg2 = (char *) 0 ; + char *arg3 = (char *) 0 ; + int res1 ; + char *buf1 = 0 ; + int alloc1 = 0 ; + int res2 ; + char *buf2 = 0 ; + int alloc2 = 0 ; + int res3 ; + char *buf3 = 0 ; + int alloc3 = 0 ; + mxArray * _out; - if (!SWIG_check_num_args("VectorDynSize_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("reportInfo",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_AsCharPtrAndSize(argv[0], &buf1, NULL, &alloc1); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_setVal" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "reportInfo" "', argument " "1"" of type '" "char const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "VectorDynSize_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< char * >(buf1); + res2 = SWIG_AsCharPtrAndSize(argv[1], &buf2, NULL, &alloc2); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "reportInfo" "', argument " "2"" of type '" "char const *""'"); + } + arg2 = reinterpret_cast< char * >(buf2); + res3 = SWIG_AsCharPtrAndSize(argv[2], &buf3, NULL, &alloc3); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "reportInfo" "', argument " "3"" of type '" "char const *""'"); + } + arg3 = reinterpret_cast< char * >(buf3); + iDynTree::reportInfo((char const *)arg1,(char const *)arg2,(char const *)arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; + if (alloc1 == SWIG_NEWOBJ) delete[] buf1; + if (alloc2 == SWIG_NEWOBJ) delete[] buf2; + if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 0; fail: + if (alloc1 == SWIG_NEWOBJ) delete[] buf1; + if (alloc2 == SWIG_NEWOBJ) delete[] buf2; + if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 1; } -int _wrap_VectorDynSize_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_reportDebug(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + char *arg1 = (char *) 0 ; + char *arg2 = (char *) 0 ; + char *arg3 = (char *) 0 ; + int res1 ; + char *buf1 = 0 ; + int alloc1 = 0 ; + int res2 ; + char *buf2 = 0 ; + int alloc2 = 0 ; + int res3 ; + char *buf3 = 0 ; + int alloc3 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("reportDebug",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_AsCharPtrAndSize(argv[0], &buf1, NULL, &alloc1); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_begin" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "reportDebug" "', argument " "1"" of type '" "char const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)((iDynTree::VectorDynSize const *)arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< char * >(buf1); + res2 = SWIG_AsCharPtrAndSize(argv[1], &buf2, NULL, &alloc2); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "reportDebug" "', argument " "2"" of type '" "char const *""'"); + } + arg2 = reinterpret_cast< char * >(buf2); + res3 = SWIG_AsCharPtrAndSize(argv[2], &buf3, NULL, &alloc3); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "reportDebug" "', argument " "3"" of type '" "char const *""'"); + } + arg3 = reinterpret_cast< char * >(buf3); + iDynTree::reportDebug((char const *)arg1,(char const *)arg2,(char const *)arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; + if (alloc1 == SWIG_NEWOBJ) delete[] buf1; + if (alloc2 == SWIG_NEWOBJ) delete[] buf2; + if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 0; fail: + if (alloc1 == SWIG_NEWOBJ) delete[] buf1; + if (alloc2 == SWIG_NEWOBJ) delete[] buf2; + if (alloc3 == SWIG_NEWOBJ) delete[] buf3; return 1; } -int _wrap_VectorDynSize_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_IndexRange_offset_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; + std::ptrdiff_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_end",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexRange_offset_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_end" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_offset_set" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)((iDynTree::VectorDynSize const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexRange_offset_set" "', argument " "2"" of type '" "std::ptrdiff_t""'"); + } + arg2 = static_cast< std::ptrdiff_t >(val2); + if (arg1) (arg1)->offset = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13725,23 +13809,23 @@ int _wrap_VectorDynSize_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_VectorDynSize_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_IndexRange_offset_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::ptrdiff_t result; - if (!SWIG_check_num_args("VectorDynSize_cbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexRange_offset_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_cbegin" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_offset_get" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)((iDynTree::VectorDynSize const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + result = ((arg1)->offset); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13749,23 +13833,30 @@ int _wrap_VectorDynSize_cbegin(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_VectorDynSize_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_IndexRange_size_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; + std::ptrdiff_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexRange_size_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_cend" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_size_set" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)((iDynTree::VectorDynSize const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IndexRange_size_set" "', argument " "2"" of type '" "std::ptrdiff_t""'"); + } + arg2 = static_cast< std::ptrdiff_t >(val2); + if (arg1) (arg1)->size = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13773,23 +13864,23 @@ int _wrap_VectorDynSize_cend(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_VectorDynSize_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_IndexRange_size_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::ptrdiff_t result; - if (!SWIG_check_num_args("VectorDynSize_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexRange_size_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_begin" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_size_get" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + result = ((arg1)->size); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13797,51 +13888,40 @@ int _wrap_VectorDynSize_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_VectorDynSize_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_VectorDynSize_begin__SWIG_1(resc,resv,argc,argv); - } +int _wrap_IndexRange_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IndexRange_isValid",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_VectorDynSize_begin__SWIG_0(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IndexRange_isValid" "', argument " "1"" of type '" "iDynTree::IndexRange const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorDynSize::begin() const\n" - " iDynTree::VectorDynSize::begin()\n"); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + result = (bool)((iDynTree::IndexRange const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_VectorDynSize_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_IndexRange_InvalidRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - double *result = 0 ; + iDynTree::IndexRange result; - if (!SWIG_check_num_args("VectorDynSize_end",argc,1,1,0)) { + if (!SWIG_check_num_args("IndexRange_InvalidRange",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_end" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)(arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + (void)argv; + result = iDynTree::IndexRange::InvalidRange(); + _out = SWIG_NewPointerObj((new iDynTree::IndexRange(static_cast< const iDynTree::IndexRange& >(result))), SWIGTYPE_p_iDynTree__IndexRange, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13849,51 +13929,43 @@ int _wrap_VectorDynSize_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_VectorDynSize_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_VectorDynSize_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_VectorDynSize_end__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_new_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::IndexRange *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorDynSize::end() const\n" - " iDynTree::VectorDynSize::end()\n"); + if (!SWIG_check_num_args("new_IndexRange",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::IndexRange *)new iDynTree::IndexRange(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IndexRange, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_VectorDynSize_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_delete_IndexRange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IndexRange *arg1 = (iDynTree::IndexRange *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("VectorDynSize_size",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_IndexRange",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IndexRange, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_size" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_IndexRange" "', argument " "1"" of type '" "iDynTree::IndexRange *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = ((iDynTree::VectorDynSize const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::IndexRange * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13901,23 +13973,43 @@ int _wrap_VectorDynSize_size(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_VectorDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_checkDoublesAreEqual__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = 0 ; + double *arg2 = 0 ; + double arg3 ; + double temp1 ; + double val1 ; + int ecode1 = 0 ; + double temp2 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("VectorDynSize_data",argc,1,1,0)) { + if (!SWIG_check_num_args("checkDoublesAreEqual",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_data" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "checkDoublesAreEqual" "', argument " "1"" of type '" "double""'"); + } + temp1 = static_cast< double >(val1); + arg1 = &temp1; + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "checkDoublesAreEqual" "', argument " "2"" of type '" "double""'"); + } + temp2 = static_cast< double >(val2); + arg2 = &temp2; + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "checkDoublesAreEqual" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)iDynTree::checkDoublesAreEqual((double const &)*arg1,(double const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13925,22 +14017,100 @@ int _wrap_VectorDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_VectorDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_checkDoublesAreEqual__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = 0 ; + double *arg2 = 0 ; + double temp1 ; + double val1 ; + int ecode1 = 0 ; + double temp2 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("VectorDynSize_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("checkDoublesAreEqual",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_zero" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "checkDoublesAreEqual" "', argument " "1"" of type '" "double""'"); + } + temp1 = static_cast< double >(val1); + arg1 = &temp1; + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "checkDoublesAreEqual" "', argument " "2"" of type '" "double""'"); + } + temp2 = static_cast< double >(val2); + arg2 = &temp2; + result = (bool)iDynTree::checkDoublesAreEqual((double const &)*arg1,(double const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_checkDoublesAreEqual(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_checkDoublesAreEqual__SWIG_1(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_checkDoublesAreEqual__SWIG_0(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'checkDoublesAreEqual'." + " Possible C/C++ prototypes are:\n" + " iDynTree::checkDoublesAreEqual(double const &,double const &,double)\n" + " iDynTree::checkDoublesAreEqual(double const &,double const &)\n"); + return 1; +} + + +int _wrap_new_MatrixDynSize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::MatrixDynSize *result = 0 ; + + if (!SWIG_check_num_args("new_MatrixDynSize",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13948,30 +14118,31 @@ int _wrap_VectorDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_VectorDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_new_MatrixDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; + size_t val1 ; + int ecode1 = 0 ; size_t val2 ; int ecode2 = 0 ; mxArray * _out; + iDynTree::MatrixDynSize *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("new_MatrixDynSize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_reserve" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_reserve" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_MatrixDynSize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - (arg1)->reserve(arg2); - _out = (mxArray*)0; + result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -13979,30 +14150,39 @@ int _wrap_VectorDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_VectorDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; +int _wrap_new_MatrixDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; + iDynTree::MatrixDynSize *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("new_MatrixDynSize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_resize" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_resize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_MatrixDynSize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_MatrixDynSize" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14010,231 +14190,26 @@ int _wrap_VectorDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_VectorDynSize_shrink_to_fit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; +int _wrap_new_MatrixDynSize__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; + iDynTree::MatrixDynSize *result = 0 ; - if (!SWIG_check_num_args("VectorDynSize_shrink_to_fit",argc,1,1,0)) { + if (!SWIG_check_num_args("new_MatrixDynSize",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_shrink_to_fit" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const &""'"); } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - (arg1)->shrink_to_fit(); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - size_t result; - - if (!SWIG_check_num_args("VectorDynSize_capacity",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_capacity" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = ((iDynTree::VectorDynSize const *)arg1)->capacity(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("VectorDynSize_fillBuffer",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSize_fillBuffer" "', argument " "2"" of type '" "double *""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorDynSize const *)arg1)->fillBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("VectorDynSize_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_toString" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = ((iDynTree::VectorDynSize const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("VectorDynSize_display",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_display" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = ((iDynTree::VectorDynSize const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - mxArray *result = 0 ; - - if (!SWIG_check_num_args("VectorDynSize_toMatlab",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - result = (mxArray *)iDynTree_VectorDynSize_toMatlab((iDynTree::VectorDynSize const *)arg1); - _out = result; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_VectorDynSize_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("VectorDynSize_fromMatlab",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - arg2 = argv[1]; - iDynTree_VectorDynSize_fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix1x6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::MatrixFixSize< 1,6 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix1x6",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix1x6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - mxArray * _out; - iDynTree::MatrixFixSize< 1,6 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix1x6",argc,3,3,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "double const *""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const &""'"); } - arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix1x6" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix1x6" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize((iDynTree::MatrixDynSize const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14242,29 +14217,29 @@ int _wrap_new_Matrix1x6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix1x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_MatrixDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 1,6 > *result = 0 ; + iDynTree::MatrixDynSize *result = 0 ; - if (!SWIG_check_num_args("new_Matrix1x6",argc,1,1,0)) { + if (!SWIG_check_num_args("new_MatrixDynSize",argc,1,1,0)) { SWIG_fail; } { res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); + result = (iDynTree::MatrixDynSize *)new iDynTree::MatrixDynSize(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14272,9 +14247,18 @@ int _wrap_new_Matrix1x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_MatrixDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Matrix1x6__SWIG_0(resc,resv,argc,argv); + return _wrap_new_MatrixDynSize__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_MatrixDynSize__SWIG_3(resc,resv,argc,argv); + } } if (argc == 1) { int _v; @@ -14282,7 +14266,23 @@ int _wrap_new_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Matrix1x6__SWIG_2(resc,resv,argc,argv); + return _wrap_new_MatrixDynSize__SWIG_4(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_MatrixDynSize__SWIG_1(resc,resv,argc,argv); + } } } if (argc == 3) { @@ -14301,23 +14301,52 @@ int _wrap_new_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Matrix1x6__SWIG_1(resc,resv,argc,argv); + return _wrap_new_MatrixDynSize__SWIG_2(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix1x6'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_MatrixDynSize'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); + " iDynTree::MatrixDynSize::MatrixDynSize()\n" + " iDynTree::MatrixDynSize::MatrixDynSize(std::size_t,std::size_t)\n" + " iDynTree::MatrixDynSize::MatrixDynSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixDynSize::MatrixDynSize(iDynTree::MatrixDynSize const &)\n" + " iDynTree::MatrixDynSize::MatrixDynSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Matrix1x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_delete_MatrixDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_MatrixDynSize",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_MatrixDynSize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_MatrixDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -14329,25 +14358,25 @@ int _wrap_Matrix1x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix1x6_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSize_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_paren" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->operator ()(arg2,arg3); + result = (double)((iDynTree::MatrixDynSize const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -14356,8 +14385,8 @@ int _wrap_Matrix1x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix1x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -14369,22 +14398,22 @@ int _wrap_Matrix1x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix1x6_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSize_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_paren" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); result = (double *) &(arg1)->operator ()(arg2,arg3); @@ -14396,11 +14425,11 @@ int _wrap_Matrix1x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix1x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_MatrixDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -14413,7 +14442,7 @@ int _wrap_Matrix1x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix1x6_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_MatrixDynSize_paren__SWIG_0(resc,resv,argc,argv); } } } @@ -14421,7 +14450,7 @@ int _wrap_Matrix1x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixDynSize, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -14434,22 +14463,22 @@ int _wrap_Matrix1x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix1x6_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_MatrixDynSize_paren__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix1x6_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'MatrixDynSize_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 1,6 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 1,6 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::MatrixDynSize::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixDynSize::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Matrix1x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -14461,25 +14490,25 @@ int _wrap_Matrix1x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix1x6_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("MatrixDynSize_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_getVal" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_getVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_getVal" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->getVal(arg2,arg3); + result = (double)((iDynTree::MatrixDynSize const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -14488,8 +14517,8 @@ int _wrap_Matrix1x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix1x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; std::size_t arg2 ; std::size_t arg3 ; double arg4 ; @@ -14504,27 +14533,27 @@ int _wrap_Matrix1x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) mxArray * _out; bool result; - if (!SWIG_check_num_args("Matrix1x6_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("MatrixDynSize_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_setVal" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_setVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_setVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_setVal" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); ecode4 = SWIG_AsVal_double(argv[3], &val4); if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix1x6_setVal" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "MatrixDynSize_setVal" "', argument " "4"" of type '" "double""'"); } arg4 = static_cast< double >(val4); result = (bool)(arg1)->setVal(arg2,arg3,arg4); @@ -14536,22 +14565,22 @@ int _wrap_Matrix1x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix1x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix1x6_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_rows" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->rows(); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = ((iDynTree::MatrixDynSize const *)arg1)->rows(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -14560,22 +14589,22 @@ int _wrap_Matrix1x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix1x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix1x6_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_cols" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->cols(); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = ((iDynTree::MatrixDynSize const *)arg1)->cols(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -14584,21 +14613,21 @@ int _wrap_Matrix1x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix1x6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix1x6_data",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_data" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; @@ -14608,20 +14637,20 @@ int _wrap_Matrix1x6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix1x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix1x6_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_zero" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -14631,29 +14660,37 @@ int _wrap_Matrix1x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix1x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_MatrixDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix1x6_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSize_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix1x6_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_resize" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->fillRowMajorBuffer(arg2); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "MatrixDynSize_resize" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + (arg1)->resize(arg2,arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -14662,29 +14699,29 @@ int _wrap_Matrix1x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix1x6_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_MatrixDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix1x6_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSize_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix1x6_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_reserve" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->fillColMajorBuffer(arg2); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "MatrixDynSize_reserve" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + (arg1)->reserve(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -14693,23 +14730,23 @@ int _wrap_Matrix1x6_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix1x6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + size_t result; - if (!SWIG_check_num_args("Matrix1x6_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_capacity" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = ((iDynTree::MatrixDynSize const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14717,23 +14754,22 @@ int _wrap_Matrix1x6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix1x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_shrink_to_fit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("Matrix1x6_display",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_shrink_to_fit",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_shrink_to_fit" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + (arg1)->shrink_to_fit(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14741,23 +14777,30 @@ int _wrap_Matrix1x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Matrix1x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix1x6_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_1_Sc_6_Sg__toMatlab((iDynTree::MatrixFixSize< 1,6 > const *)arg1); - _out = result; + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSize_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixDynSize const *)arg1)->fillRowMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14765,23 +14808,29 @@ int _wrap_Matrix1x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix1x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_MatrixDynSize_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix1x6_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("MatrixDynSize_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_1_Sc_6_Sg__fromMatlab(arg1,arg2); + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MatrixDynSize_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixDynSize const *)arg1)->fillColMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -14790,25 +14839,95 @@ int _wrap_Matrix1x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_delete_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; +int _wrap_MatrixDynSize_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::string result; - int is_owned; - if (!SWIG_check_num_args("delete_Matrix1x6",argc,1,1,0)) { + if (!SWIG_check_num_args("MatrixDynSize_toString",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_toString" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = ((iDynTree::MatrixDynSize const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_MatrixDynSize_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("MatrixDynSize_display",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_display" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = ((iDynTree::MatrixDynSize const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_MatrixDynSize_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + mxArray *result = 0 ; + + if (!SWIG_check_num_args("MatrixDynSize_toMatlab",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + result = (mxArray *)iDynTree_MatrixDynSize_toMatlab((iDynTree::MatrixDynSize const *)arg1); + _out = result; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_MatrixDynSize_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixDynSize *arg1 = (iDynTree::MatrixDynSize *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("MatrixDynSize_fromMatlab",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MatrixDynSize_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixDynSize *""'"); } + arg1 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp1); + arg2 = argv[1]; + iDynTree_MatrixDynSize_fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -14817,16 +14936,16 @@ int _wrap_delete_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Matrix2x3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SparseMatrixRowMajor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::MatrixFixSize< 2,3 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix2x3",argc,0,0,0)) { + if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); + result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14834,39 +14953,31 @@ int _wrap_new_Matrix2x3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix2x3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_new_SparseMatrixRowMajor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; + size_t val1 ; + int ecode1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 2,3 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix2x3",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "double const *""'"); - } - arg1 = reinterpret_cast< double * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixRowMajor" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix2x3" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixRowMajor" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix2x3" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); + result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14874,29 +14985,42 @@ int _wrap_new_Matrix2x3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix2x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; - int res1 = 0 ; +int _wrap_new_SparseMatrixRowMajor__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + std::size_t arg2 ; + iDynTree::VectorDynSize *arg3 = 0 ; + size_t val1 ; + int ecode1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 2,3 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::RowMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix2x3",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SparseMatrixRowMajor",argc,3,3,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixRowMajor" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixRowMajor" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SparseMatrixRowMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } - result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SparseMatrixRowMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + result = (iDynTree::SparseMatrix< iDynTree::RowMajor > *)new iDynTree::SparseMatrix< iDynTree::RowMajor >(arg1,arg2,(iDynTree::VectorDynSize const &)*arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14904,52 +15028,110 @@ int _wrap_new_Matrix2x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix2x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SparseMatrixRowMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Matrix2x3__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SparseMatrixRowMajor__SWIG_0(resc,resv,argc,argv); } - if (argc == 1) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_Matrix2x3__SWIG_2(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_SparseMatrixRowMajor__SWIG_1(resc,resv,argc,argv); + } } } if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { { int res = SWIG_AsVal_size_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Matrix2x3__SWIG_1(resc,resv,argc,argv); + return _wrap_new_SparseMatrixRowMajor__SWIG_2(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix2x3'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SparseMatrixRowMajor'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); + " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix()\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix(std::size_t,std::size_t)\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::SparseMatrix(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); return 1; } -int _wrap_Matrix2x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; +int _wrap_delete_SparseMatrixRowMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_SparseMatrixRowMajor",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SparseMatrixRowMajor" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); + } + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SparseMatrixRowMajor_numberOfNonZeros(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("SparseMatrixRowMajor_numberOfNonZeros",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_numberOfNonZeros" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->numberOfNonZeros(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SparseMatrixRowMajor_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -14959,28 +15141,27 @@ int _wrap_Matrix2x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * size_t val3 ; int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("Matrix2x3_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + (arg1)->resize(arg2,arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -14988,39 +15169,49 @@ int _wrap_Matrix2x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix2x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; + iDynTree::VectorDynSize *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; size_t val3 ; int ecode3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Matrix2x3_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_resize",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SparseMatrixRowMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); + (arg1)->resize(arg2,arg3,(iDynTree::VectorDynSize const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15028,11 +15219,11 @@ int _wrap_Matrix2x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix2x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SparseMatrixRowMajor_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -15045,15 +15236,15 @@ int _wrap_Matrix2x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix2x3_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_SparseMatrixRowMajor_resize__SWIG_0(resc,resv,argc,argv); } } } } - if (argc == 3) { + if (argc == 4) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -15066,53 +15257,49 @@ int _wrap_Matrix2x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix2x3_paren__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SparseMatrixRowMajor_resize__SWIG_1(resc,resv,argc,argv); + } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix2x3_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 2,3 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 2,3 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::SparseMatrix< iDynTree::RowMajor >::resize(std::size_t,std::size_t)\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::resize(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); return 1; } -int _wrap_Matrix2x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("Matrix2x3_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_reserve" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_reserve" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_getVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->getVal(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15120,47 +15307,22 @@ int _wrap_Matrix2x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix2x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; +int _wrap_SparseMatrixRowMajor_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("Matrix2x3_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_zero" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_setVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix2x3_setVal" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15168,124 +15330,32 @@ int _wrap_Matrix2x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix2x3_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_setFromConstTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; + iDynTree::Triplets *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("Matrix2x3_rows",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("Matrix2x3_cols",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->cols(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Matrix2x3_data",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix2x3_zero",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix2x3_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_setFromConstTriplets",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix2x3_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->fillRowMajorBuffer(arg2); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); + (arg1)->setFromConstTriplets((iDynTree::Triplets const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -15294,153 +15364,32 @@ int _wrap_Matrix2x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix2x3_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_SparseMatrixRowMajor_setFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; + iDynTree::Triplets *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix2x3_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_setFromTriplets",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix2x3_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Matrix2x3_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Matrix2x3_display",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - mxArray *result = 0 ; - - if (!SWIG_check_num_args("Matrix2x3_toMatlab",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_2_Sc_3_Sg__toMatlab((iDynTree::MatrixFixSize< 2,3 > const *)arg1); - _out = result; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix2x3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix2x3_fromMatlab",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_2_Sc_3_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_delete_Matrix2x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - int is_owned; - if (!SWIG_check_num_args("delete_Matrix2x3",argc,1,1,0)) { - SWIG_fail; - } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); - if (is_owned) { - delete arg1; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); } + arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); + (arg1)->setFromTriplets(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -15449,86 +15398,42 @@ int _wrap_delete_Matrix2x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Matrix3x3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::MatrixFixSize< 3,3 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix3x3",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix3x3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_SparseMatrixRowMajor_sparseMatrixFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; + iDynTree::Triplets *arg3 = 0 ; + size_t val1 ; + int ecode1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 3,3 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::RowMajor > result; - if (!SWIG_check_num_args("new_Matrix3x3",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_sparseMatrixFromTriplets",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "double const *""'"); - } - arg1 = reinterpret_cast< double * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix3x3" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix3x3" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix3x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::MatrixFixSize< 3,3 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix3x3",argc,1,1,0)) { - SWIG_fail; + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Triplets, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixRowMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); } - result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); + arg3 = reinterpret_cast< iDynTree::Triplets * >(argp3); + result = iDynTree::SparseMatrix< iDynTree::RowMajor >::SWIGTEMPLATEDISAMBIGUATOR sparseMatrixFromTriplets(arg1,arg2,(iDynTree::Triplets const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::SparseMatrix< iDynTree::RowMajor >(static_cast< const iDynTree::SparseMatrix< iDynTree::RowMajor >& >(result))), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15536,52 +15441,8 @@ int _wrap_new_Matrix3x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix3x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Matrix3x3__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Matrix3x3__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Matrix3x3__SWIG_1(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix3x3'." - " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); - return 1; -} - - -int _wrap_Matrix3x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -15593,25 +15454,25 @@ int _wrap_Matrix3x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix3x3_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->operator ()(arg2,arg3); + result = (double)((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -15620,8 +15481,8 @@ int _wrap_Matrix3x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix3x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -15633,22 +15494,22 @@ int _wrap_Matrix3x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix3x3_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); result = (double *) &(arg1)->operator ()(arg2,arg3); @@ -15660,11 +15521,11 @@ int _wrap_Matrix3x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix3x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SparseMatrixRowMajor_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -15677,7 +15538,7 @@ int _wrap_Matrix3x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix3x3_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_SparseMatrixRowMajor_paren__SWIG_0(resc,resv,argc,argv); } } } @@ -15685,7 +15546,7 @@ int _wrap_Matrix3x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -15698,22 +15559,22 @@ int _wrap_Matrix3x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix3x3_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_SparseMatrixRowMajor_paren__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix3x3_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 3,3 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 3,3 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::SparseMatrix< iDynTree::RowMajor >::operator ()(std::size_t,std::size_t) const\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::operator ()(std::size_t,std::size_t)\n"); return 1; } -int _wrap_Matrix3x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_getValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -15725,25 +15586,25 @@ int _wrap_Matrix3x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix3x3_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_getValue",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_getVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_getValue" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->getVal(arg2,arg3); + result = (double)((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->getValue(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -15752,8 +15613,8 @@ int _wrap_Matrix3x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix3x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_setValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; double arg4 ; @@ -15766,33 +15627,32 @@ int _wrap_Matrix3x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) double val4 ; int ecode4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("Matrix3x3_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_setValue",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_setVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_setVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); ecode4 = SWIG_AsVal_double(argv[3], &val4); if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix3x3_setVal" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "SparseMatrixRowMajor_setValue" "', argument " "4"" of type '" "double""'"); } arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + (arg1)->setValue(arg2,arg3,arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15800,22 +15660,22 @@ int _wrap_Matrix3x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix3x3_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix3x3_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_rows" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->rows(); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->rows(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -15824,22 +15684,22 @@ int _wrap_Matrix3x3_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix3x3_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_columns(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix3x3_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_columns",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_columns" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->cols(); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->columns(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -15848,46 +15708,31 @@ int _wrap_Matrix3x3_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix3x3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Matrix3x3_data",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix3x3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_description__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; + bool arg2 ; void *argp1 = 0 ; int res1 = 0 ; + bool val2 ; + int ecode2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("Matrix3x3_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_description",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + ecode2 = SWIG_AsVal_bool(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixRowMajor_description" "', argument " "2"" of type '" "bool""'"); + } + arg2 = static_cast< bool >(val2); + result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->description(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15895,30 +15740,23 @@ int _wrap_Matrix3x3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix3x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_SparseMatrixRowMajor_description__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("Matrix3x3_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_description",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix3x3_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->fillRowMajorBuffer(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1)->description(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -15926,78 +15764,57 @@ int _wrap_Matrix3x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix3x3_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix3x3_fillColMajorBuffer",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); +int _wrap_SparseMatrixRowMajor_description(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SparseMatrixRowMajor_description__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix3x3_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_bool(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_SparseMatrixRowMajor_description__SWIG_0(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix3x3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - if (!SWIG_check_num_args("Matrix3x3_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixRowMajor_description'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::description(bool) const\n" + " iDynTree::SparseMatrix< iDynTree::RowMajor >::description() const\n"); return 1; } -int _wrap_Matrix3x3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix3x3_display",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_toMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__toMatlab((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16005,22 +15822,22 @@ int _wrap_Matrix3x3_display(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Matrix3x3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_toMatlabDense(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix3x3_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_toMatlabDense",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_toMatlabDense" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_3_Sc_3_Sg__toMatlab((iDynTree::MatrixFixSize< 3,3 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); + result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__toMatlabDense((iDynTree::SparseMatrix< iDynTree::RowMajor > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -16029,50 +15846,23 @@ int _wrap_Matrix3x3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix3x3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; +int _wrap_SparseMatrixRowMajor_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::RowMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::RowMajor > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix3x3_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixRowMajor_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixRowMajor_fromMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::RowMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::RowMajor > * >(argp1); arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_3_Sc_3_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_delete_Matrix3x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - int is_owned; - if (!SWIG_check_num_args("delete_Matrix3x3",argc,1,1,0)) { - SWIG_fail; - } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); - if (is_owned) { - delete arg1; - } + iDynTree_SparseMatrix_Sl_iDynTree_RowMajor_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -16081,16 +15871,16 @@ int _wrap_delete_Matrix3x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Matrix4x4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SparseMatrixColMajor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::MatrixFixSize< 4,4 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix4x4",argc,0,0,0)) { + if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); + result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16098,39 +15888,31 @@ int _wrap_new_Matrix4x4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix4x4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_new_SparseMatrixColMajor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; + size_t val1 ; + int ecode1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 4,4 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix4x4",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "double const *""'"); - } - arg1 = reinterpret_cast< double * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixColMajor" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix4x4" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixColMajor" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix4x4" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); + result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16138,29 +15920,42 @@ int _wrap_new_Matrix4x4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix4x4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; - int res1 = 0 ; +int _wrap_new_SparseMatrixColMajor__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + std::size_t arg2 ; + iDynTree::VectorDynSize *arg3 = 0 ; + size_t val1 ; + int ecode1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 4,4 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix4x4",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SparseMatrixColMajor",argc,3,3,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SparseMatrixColMajor" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_SparseMatrixColMajor" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SparseMatrixColMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } - result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SparseMatrixColMajor" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + result = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *)new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(arg1,arg2,(iDynTree::VectorDynSize const &)*arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16168,52 +15963,110 @@ int _wrap_new_Matrix4x4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix4x4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SparseMatrixColMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Matrix4x4__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SparseMatrixColMajor__SWIG_0(resc,resv,argc,argv); } - if (argc == 1) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_Matrix4x4__SWIG_2(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_SparseMatrixColMajor__SWIG_1(resc,resv,argc,argv); + } } } if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { { int res = SWIG_AsVal_size_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Matrix4x4__SWIG_1(resc,resv,argc,argv); + return _wrap_new_SparseMatrixColMajor__SWIG_2(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix4x4'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SparseMatrixColMajor'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix()\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix(std::size_t,std::size_t)\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SparseMatrix(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); return 1; } -int _wrap_Matrix4x4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; +int _wrap_delete_SparseMatrixColMajor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_SparseMatrixColMajor",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SparseMatrixColMajor" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); + } + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SparseMatrixColMajor_numberOfNonZeros(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("SparseMatrixColMajor_numberOfNonZeros",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_numberOfNonZeros" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->numberOfNonZeros(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SparseMatrixColMajor_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -16223,28 +16076,27 @@ int _wrap_Matrix4x4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * size_t val3 ; int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("Matrix4x4_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); + (arg1)->resize(arg2,arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16252,39 +16104,49 @@ int _wrap_Matrix4x4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix4x4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; +int _wrap_SparseMatrixColMajor_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; + iDynTree::VectorDynSize *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; size_t val3 ; int ecode3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Matrix4x4_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_resize",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_resize" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_resize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_resize" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SparseMatrixColMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_resize" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); + (arg1)->resize(arg2,arg3,(iDynTree::VectorDynSize const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16292,11 +16154,11 @@ int _wrap_Matrix4x4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix4x4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SparseMatrixColMajor_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -16309,15 +16171,15 @@ int _wrap_Matrix4x4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix4x4_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_SparseMatrixColMajor_resize__SWIG_0(resc,resv,argc,argv); } } } } - if (argc == 3) { + if (argc == 4) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -16330,173 +16192,49 @@ int _wrap_Matrix4x4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix4x4_paren__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SparseMatrixColMajor_resize__SWIG_1(resc,resv,argc,argv); + } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix4x4_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 4,4 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 4,4 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::resize(std::size_t,std::size_t)\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::resize(std::size_t,std::size_t,iDynTree::VectorDynSize const &)\n"); return 1; } -int _wrap_Matrix4x4_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; +int _wrap_SparseMatrixColMajor_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - double result; - if (!SWIG_check_num_args("Matrix4x4_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_reserve" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_reserve" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_getVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->getVal(arg2,arg3); - _out = SWIG_From_double(static_cast< double >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Matrix4x4_setVal",argc,4,4,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_setVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix4x4_setVal" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("Matrix4x4_rows",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("Matrix4x4_cols",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->cols(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Matrix4x4_data",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16504,20 +16242,20 @@ int _wrap_Matrix4x4_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix4x4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; +int _wrap_SparseMatrixColMajor_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix4x4_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_zero" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -16527,29 +16265,32 @@ int _wrap_Matrix4x4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix4x4_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_SparseMatrixColMajor_setFromConstTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; + iDynTree::Triplets *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix4x4_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_setFromConstTriplets",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix4x4_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->fillRowMajorBuffer(arg2); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_setFromConstTriplets" "', argument " "2"" of type '" "iDynTree::Triplets const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); + (arg1)->setFromConstTriplets((iDynTree::Triplets const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -16558,153 +16299,32 @@ int _wrap_Matrix4x4_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix4x4_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_SparseMatrixColMajor_setFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; + iDynTree::Triplets *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix4x4_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_setFromTriplets",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Triplets, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix4x4_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Matrix4x4_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Matrix4x4_display",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - mxArray *result = 0 ; - - if (!SWIG_check_num_args("Matrix4x4_toMatlab",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_4_Sc_4_Sg__toMatlab((iDynTree::MatrixFixSize< 4,4 > const *)arg1); - _out = result; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix4x4_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix4x4_fromMatlab",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_4_Sc_4_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_delete_Matrix4x4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - int is_owned; - if (!SWIG_check_num_args("delete_Matrix4x4",argc,1,1,0)) { - SWIG_fail; - } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); - if (is_owned) { - delete arg1; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_setFromTriplets" "', argument " "2"" of type '" "iDynTree::Triplets &""'"); } + arg2 = reinterpret_cast< iDynTree::Triplets * >(argp2); + (arg1)->setFromTriplets(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -16713,86 +16333,42 @@ int _wrap_delete_Matrix4x4(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Matrix6x6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::MatrixFixSize< 6,6 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix6x6",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix6x6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_SparseMatrixColMajor_sparseMatrixFromTriplets(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; std::size_t arg2 ; - std::size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; + iDynTree::Triplets *arg3 = 0 ; + size_t val1 ; + int ecode1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 6,6 > *result = 0 ; + iDynTree::SparseMatrix< iDynTree::ColumnMajor > result; - if (!SWIG_check_num_args("new_Matrix6x6",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_sparseMatrixFromTriplets",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "double const *""'"); - } - arg1 = reinterpret_cast< double * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix6x6" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix6x6" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Matrix6x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::MatrixFixSize< 6,6 > *result = 0 ; - - if (!SWIG_check_num_args("new_Matrix6x6",argc,1,1,0)) { - SWIG_fail; + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Triplets, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SparseMatrixColMajor_sparseMatrixFromTriplets" "', argument " "3"" of type '" "iDynTree::Triplets const &""'"); } - result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); + arg3 = reinterpret_cast< iDynTree::Triplets * >(argp3); + result = iDynTree::SparseMatrix< iDynTree::ColumnMajor >::SWIGTEMPLATEDISAMBIGUATOR sparseMatrixFromTriplets(arg1,arg2,(iDynTree::Triplets const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::SparseMatrix< iDynTree::ColumnMajor >(static_cast< const iDynTree::SparseMatrix< iDynTree::ColumnMajor >& >(result))), SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -16800,52 +16376,8 @@ int _wrap_new_Matrix6x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Matrix6x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Matrix6x6__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Matrix6x6__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Matrix6x6__SWIG_1(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix6x6'." - " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); - return 1; -} - - -int _wrap_Matrix6x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -16857,25 +16389,25 @@ int _wrap_Matrix6x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix6x6_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->operator ()(arg2,arg3); + result = (double)((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -16884,8 +16416,8 @@ int _wrap_Matrix6x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix6x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -16897,22 +16429,22 @@ int _wrap_Matrix6x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x6_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_paren" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); result = (double *) &(arg1)->operator ()(arg2,arg3); @@ -16924,11 +16456,11 @@ int _wrap_Matrix6x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Matrix6x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SparseMatrixColMajor_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -16941,7 +16473,7 @@ int _wrap_Matrix6x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix6x6_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_SparseMatrixColMajor_paren__SWIG_0(resc,resv,argc,argv); } } } @@ -16949,7 +16481,7 @@ int _wrap_Matrix6x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -16962,22 +16494,22 @@ int _wrap_Matrix6x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix6x6_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_SparseMatrixColMajor_paren__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix6x6_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 6,6 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 6,6 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::operator ()(std::size_t,std::size_t) const\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::operator ()(std::size_t,std::size_t)\n"); return 1; } -int _wrap_Matrix6x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_getValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -16989,25 +16521,25 @@ int _wrap_Matrix6x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix6x6_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_getValue",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_getValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_getValue" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_getVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_getValue" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->getVal(arg2,arg3); + result = (double)((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->getValue(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -17016,8 +16548,8 @@ int _wrap_Matrix6x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_setValue(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; double arg4 ; @@ -17030,33 +16562,32 @@ int _wrap_Matrix6x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) double val4 ; int ecode4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("Matrix6x6_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_setValue",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_setValue" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_setVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_setValue" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_setVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SparseMatrixColMajor_setValue" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); ecode4 = SWIG_AsVal_double(argv[3], &val4); if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix6x6_setVal" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "SparseMatrixColMajor_setValue" "', argument " "4"" of type '" "double""'"); } arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + (arg1)->setValue(arg2,arg3,arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17064,22 +16595,22 @@ int _wrap_Matrix6x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix6x6_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_rows" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->rows(); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->rows(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -17088,22 +16619,22 @@ int _wrap_Matrix6x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix6x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_columns(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix6x6_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_columns",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_columns" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->cols(); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->columns(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -17112,46 +16643,31 @@ int _wrap_Matrix6x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix6x6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Matrix6x6_data",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix6x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_description__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; + bool arg2 ; void *argp1 = 0 ; int res1 = 0 ; + bool val2 ; + int ecode2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("Matrix6x6_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_description",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + ecode2 = SWIG_AsVal_bool(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SparseMatrixColMajor_description" "', argument " "2"" of type '" "bool""'"); + } + arg2 = static_cast< bool >(val2); + result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->description(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17159,30 +16675,23 @@ int _wrap_Matrix6x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Matrix6x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_SparseMatrixColMajor_description__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("Matrix6x6_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_description",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x6_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_description" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->fillRowMajorBuffer(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = ((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1)->description(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17190,78 +16699,57 @@ int _wrap_Matrix6x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Matrix6x6_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Matrix6x6_fillColMajorBuffer",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); +int _wrap_SparseMatrixColMajor_description(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SparseMatrixColMajor_description__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x6_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_bool(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_SparseMatrixColMajor_description__SWIG_0(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Matrix6x6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - if (!SWIG_check_num_args("Matrix6x6_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SparseMatrixColMajor_description'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::description(bool) const\n" + " iDynTree::SparseMatrix< iDynTree::ColumnMajor >::description() const\n"); return 1; } -int _wrap_Matrix6x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix6x6_display",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_toMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__toMatlab((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17269,22 +16757,22 @@ int _wrap_Matrix6x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Matrix6x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_toMatlabDense(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix6x6_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_toMatlabDense",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_toMatlabDense" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_6_Sc_6_Sg__toMatlab((iDynTree::MatrixFixSize< 6,6 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); + result = (mxArray *)iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__toMatlabDense((iDynTree::SparseMatrix< iDynTree::ColumnMajor > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -17293,23 +16781,23 @@ int _wrap_Matrix6x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix6x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; +int _wrap_SparseMatrixColMajor_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SparseMatrix< iDynTree::ColumnMajor > *arg1 = (iDynTree::SparseMatrix< iDynTree::ColumnMajor > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix6x6_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("SparseMatrixColMajor_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SparseMatrixT_iDynTree__ColumnMajor_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SparseMatrixColMajor_fromMatlab" "', argument " "1"" of type '" "iDynTree::SparseMatrix< iDynTree::ColumnMajor > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::SparseMatrix< iDynTree::ColumnMajor > * >(argp1); arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_6_Sc_6_Sg__fromMatlab(arg1,arg2); + iDynTree_SparseMatrix_Sl_iDynTree_ColumnMajor_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -17318,26 +16806,16 @@ int _wrap_Matrix6x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_delete_Matrix6x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_VectorDynSize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::VectorDynSize *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_Matrix6x6",argc,1,1,0)) { + if (!SWIG_check_num_args("new_VectorDynSize",argc,0,0,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17345,16 +16823,23 @@ int _wrap_delete_Matrix6x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Matrix6x10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_VectorDynSize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 6,10 > *result = 0 ; + iDynTree::VectorDynSize *result = 0 ; - if (!SWIG_check_num_args("new_Matrix6x10",argc,0,0,0)) { + if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17362,39 +16847,31 @@ int _wrap_new_Matrix6x10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_Matrix6x10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_VectorDynSize__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 6,10 > *result = 0 ; + iDynTree::VectorDynSize *result = 0 ; - if (!SWIG_check_num_args("new_Matrix6x10",argc,3,3,0)) { + if (!SWIG_check_num_args("new_VectorDynSize",argc,2,2,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix6x10" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_VectorDynSize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix6x10" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); + result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17402,29 +16879,56 @@ int _wrap_new_Matrix6x10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_Matrix6x10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; +int _wrap_new_VectorDynSize__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 6,10 > *result = 0 ; + iDynTree::VectorDynSize *result = 0 ; - if (!SWIG_check_num_args("new_Matrix6x10",argc,1,1,0)) { + if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize((iDynTree::VectorDynSize const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_VectorDynSize__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::VectorDynSize *result = 0 ; + + if (!SWIG_check_num_args("new_VectorDynSize",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_VectorDynSize" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); } } - result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); + result = (iDynTree::VectorDynSize *)new iDynTree::VectorDynSize(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorDynSize, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17432,20 +16936,39 @@ int _wrap_new_Matrix6x10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_VectorDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Matrix6x10__SWIG_0(resc,resv,argc,argv); + return _wrap_new_VectorDynSize__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Matrix6x10__SWIG_2(resc,resv,argc,argv); + return _wrap_new_VectorDynSize__SWIG_3(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_VectorDynSize__SWIG_4(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_VectorDynSize__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -17456,58 +16979,73 @@ int _wrap_new_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Matrix6x10__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_VectorDynSize__SWIG_2(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix6x10'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_VectorDynSize'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); + " iDynTree::VectorDynSize::VectorDynSize()\n" + " iDynTree::VectorDynSize::VectorDynSize(std::size_t)\n" + " iDynTree::VectorDynSize::VectorDynSize(double const *,std::size_t const)\n" + " iDynTree::VectorDynSize::VectorDynSize(iDynTree::VectorDynSize const &)\n" + " iDynTree::VectorDynSize::VectorDynSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_Matrix6x10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_delete_VectorDynSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_VectorDynSize",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_VectorDynSize" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix6x10_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSize_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_paren" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_paren" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->operator ()(arg2,arg3); + result = (double)((iDynTree::VectorDynSize const *)arg1)->operator ()(arg2); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -17516,38 +17054,30 @@ int _wrap_Matrix6x10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Matrix6x10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSize_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_paren" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_paren" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double *) &(arg1)->operator ()(arg2,arg3); + result = (double *) &(arg1)->operator ()(arg2); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -17556,11 +17086,11 @@ int _wrap_Matrix6x10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Matrix6x10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_VectorDynSize_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -17568,20 +17098,14 @@ int _wrap_Matrix6x10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Matrix6x10_paren__SWIG_0(resc,resv,argc,argv); - } + return _wrap_VectorDynSize_paren__SWIG_0(resc,resv,argc,argv); } } } - if (argc == 3) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -17589,57 +17113,43 @@ int _wrap_Matrix6x10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Matrix6x10_paren__SWIG_1(resc,resv,argc,argv); - } + return _wrap_VectorDynSize_paren__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix6x10_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 6,10 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 6,10 >::operator ()(std::size_t const,std::size_t const)\n"); - return 1; + " iDynTree::VectorDynSize::operator ()(std::size_t const) const\n" + " iDynTree::VectorDynSize::operator ()(std::size_t const)\n"); + return 1; } -int _wrap_Matrix6x10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix6x10_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSize_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_brace" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_brace" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_getVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->getVal(arg2,arg3); + result = (double)((iDynTree::VectorDynSize const *)arg1)->operator [](arg2); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -17648,47 +17158,31 @@ int _wrap_Matrix6x10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Matrix6x10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; - double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; mxArray * _out; - bool result; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("VectorDynSize_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_brace" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_setVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_brace" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_setVal" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix6x10_setVal" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = (bool)(arg1)->setVal(arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17696,23 +17190,71 @@ int _wrap_Matrix6x10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Matrix6x10_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_VectorDynSize_brace__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_VectorDynSize_brace__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_brace'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorDynSize::operator [](std::size_t const) const\n" + " iDynTree::VectorDynSize::operator [](std::size_t const)\n"); + return 1; +} + + +int _wrap_VectorDynSize_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::size_t result; + double result; - if (!SWIG_check_num_args("Matrix6x10_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_getVal" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->rows(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorDynSize const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17720,23 +17262,39 @@ int _wrap_Matrix6x10_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x10_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - std::size_t result; + bool result; - if (!SWIG_check_num_args("Matrix6x10_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_setVal" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->cols(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "VectorDynSize_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17744,22 +17302,22 @@ int _wrap_Matrix6x10_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_data",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_begin" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = (double *)(arg1)->data(); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)((iDynTree::VectorDynSize const *)arg1)->begin(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -17768,22 +17326,23 @@ int _wrap_Matrix6x10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_end" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)((iDynTree::VectorDynSize const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17791,30 +17350,23 @@ int _wrap_Matrix6x10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix6x10_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_VectorDynSize_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSize_cbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x10_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_cbegin" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->fillRowMajorBuffer(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)((iDynTree::VectorDynSize const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17822,30 +17374,23 @@ int _wrap_Matrix6x10_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxA } -int _wrap_Matrix6x10_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; - double *arg2 = (double *) 0 ; +int _wrap_VectorDynSize_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSize_cend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x10_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_cend" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->fillColMajorBuffer(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)((iDynTree::VectorDynSize const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17853,23 +17398,23 @@ int _wrap_Matrix6x10_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxA } -int _wrap_Matrix6x10_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_begin" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17877,23 +17422,51 @@ int _wrap_Matrix6x10_toString(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Matrix6x10_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_VectorDynSize_begin__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_VectorDynSize_begin__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorDynSize::begin() const\n" + " iDynTree::VectorDynSize::begin()\n"); + return 1; +} + + +int _wrap_VectorDynSize_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_display",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_end" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17901,23 +17474,51 @@ int _wrap_Matrix6x10_display(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix6x10_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_VectorDynSize_end__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_VectorDynSize_end__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'VectorDynSize_end'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorDynSize::end() const\n" + " iDynTree::VectorDynSize::end()\n"); + return 1; +} + + +int _wrap_VectorDynSize_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - mxArray *result = 0 ; + std::size_t result; - if (!SWIG_check_num_args("Matrix6x10_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_size" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_6_Sc_10_Sg__toMatlab((iDynTree::MatrixFixSize< 6,10 > const *)arg1); - _out = result; + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = ((iDynTree::VectorDynSize const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17925,24 +17526,23 @@ int _wrap_Matrix6x10_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Matrix6x10_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_VectorDynSize_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("Matrix6x10_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("VectorDynSize_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_data" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_6_Sc_10_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17950,25 +17550,21 @@ int _wrap_Matrix6x10_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_delete_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; +int _wrap_VectorDynSize_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_Matrix6x10",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_zero",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_zero" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -17977,16 +17573,30 @@ int _wrap_delete_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_Matrix10x16__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_VectorDynSize_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix10x16",argc,0,0,0)) { + if (!SWIG_check_num_args("VectorDynSize_reserve",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_reserve" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_reserve" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -17994,39 +17604,30 @@ int _wrap_new_Matrix10x16__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_Matrix10x16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_VectorDynSize_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; std::size_t arg2 ; - std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix10x16",argc,3,3,0)) { + if (!SWIG_check_num_args("VectorDynSize_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_resize" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - arg1 = reinterpret_cast< double * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix10x16" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "VectorDynSize_resize" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix10x16" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18034,29 +17635,22 @@ int _wrap_new_Matrix10x16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_Matrix10x16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; +int _wrap_VectorDynSize_shrink_to_fit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_Matrix10x16",argc,1,1,0)) { + if (!SWIG_check_num_args("VectorDynSize_shrink_to_fit",argc,1,1,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_shrink_to_fit" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); } - result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + (arg1)->shrink_to_fit(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18064,52 +17658,291 @@ int _wrap_new_Matrix10x16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_Matrix10x16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Matrix10x16__SWIG_0(resc,resv,argc,argv); +int _wrap_VectorDynSize_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("VectorDynSize_capacity",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Matrix10x16__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_capacity" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Matrix10x16__SWIG_1(resc,resv,argc,argv); - } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = ((iDynTree::VectorDynSize const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + double *arg2 = (double *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("VectorDynSize_fillBuffer",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "VectorDynSize_fillBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorDynSize const *)arg1)->fillBuffer(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("VectorDynSize_toString",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_toString" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = ((iDynTree::VectorDynSize const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("VectorDynSize_display",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_display" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = ((iDynTree::VectorDynSize const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + mxArray *result = 0 ; + + if (!SWIG_check_num_args("VectorDynSize_toMatlab",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorDynSize const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + result = (mxArray *)iDynTree_VectorDynSize_toMatlab((iDynTree::VectorDynSize const *)arg1); + _out = result; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_VectorDynSize_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = (iDynTree::VectorDynSize *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("VectorDynSize_fromMatlab",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorDynSize, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "VectorDynSize_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorDynSize *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + arg2 = argv[1]; + iDynTree_VectorDynSize_fromMatlab(arg1,arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Matrix1x6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::MatrixFixSize< 1,6 > *result = 0 ; + + if (!SWIG_check_num_args("new_Matrix1x6",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Matrix1x6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + mxArray * _out; + iDynTree::MatrixFixSize< 1,6 > *result = 0 ; + + if (!SWIG_check_num_args("new_Matrix1x6",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "double const *""'"); + } + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix1x6" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix1x6" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Matrix1x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::MatrixFixSize< 1,6 > *result = 0 ; + + if (!SWIG_check_num_args("new_Matrix1x6",argc,1,1,0)) { + SWIG_fail; + } + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); + } + } + result = (iDynTree::MatrixFixSize< 1,6 > *)new iDynTree::MatrixFixSize< 1,6 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Matrix1x6__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Matrix1x6__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix1x6__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix10x16'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix1x6'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize()\n" - " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" - " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); + " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 1,6 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Matrix10x16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -18121,25 +17954,25 @@ int _wrap_Matrix10x16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix10x16_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix1x6_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->operator ()(arg2,arg3); + result = (double)((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18148,8 +17981,8 @@ int _wrap_Matrix10x16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Matrix10x16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -18161,22 +17994,22 @@ int _wrap_Matrix10x16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix10x16_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix1x6_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_paren" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_paren" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); result = (double *) &(arg1)->operator ()(arg2,arg3); @@ -18188,11 +18021,11 @@ int _wrap_Matrix10x16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Matrix10x16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Matrix1x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -18205,7 +18038,7 @@ int _wrap_Matrix10x16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[] _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix10x16_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_Matrix1x6_paren__SWIG_0(resc,resv,argc,argv); } } } @@ -18213,7 +18046,7 @@ int _wrap_Matrix10x16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[] if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -18226,22 +18059,22 @@ int _wrap_Matrix10x16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[] _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Matrix10x16_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_Matrix1x6_paren__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix10x16_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix1x6_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixFixSize< 10,16 >::operator ()(std::size_t const,std::size_t const) const\n" - " iDynTree::MatrixFixSize< 10,16 >::operator ()(std::size_t const,std::size_t const)\n"); + " iDynTree::MatrixFixSize< 1,6 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 1,6 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Matrix10x16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; void *argp1 = 0 ; @@ -18253,25 +18086,25 @@ int _wrap_Matrix10x16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[ mxArray * _out; double result; - if (!SWIG_check_num_args("Matrix10x16_getVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix1x6_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_getVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_getVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_getVal" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); - result = (double)((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->getVal(arg2,arg3); + result = (double)((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18280,8 +18113,8 @@ int _wrap_Matrix10x16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix10x16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; std::size_t arg2 ; std::size_t arg3 ; double arg4 ; @@ -18296,27 +18129,27 @@ int _wrap_Matrix10x16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[ mxArray * _out; bool result; - if (!SWIG_check_num_args("Matrix10x16_setVal",argc,4,4,0)) { + if (!SWIG_check_num_args("Matrix1x6_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_setVal" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix1x6_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_setVal" "', argument " "3"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix1x6_setVal" "', argument " "3"" of type '" "std::size_t""'"); } arg3 = static_cast< std::size_t >(val3); ecode4 = SWIG_AsVal_double(argv[3], &val4); if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix10x16_setVal" "', argument " "4"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix1x6_setVal" "', argument " "4"" of type '" "double""'"); } arg4 = static_cast< double >(val4); result = (bool)(arg1)->setVal(arg2,arg3,arg4); @@ -18328,22 +18161,22 @@ int _wrap_Matrix10x16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Matrix10x16_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix10x16_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->rows(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->rows(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18352,22 +18185,22 @@ int _wrap_Matrix10x16_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix10x16_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::size_t result; - if (!SWIG_check_num_args("Matrix10x16_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->cols(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->cols(); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18376,21 +18209,21 @@ int _wrap_Matrix10x16_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix10x16_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Matrix10x16_data",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; @@ -18400,20 +18233,20 @@ int _wrap_Matrix10x16_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix10x16_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix10x16_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; @@ -18423,8 +18256,8 @@ int _wrap_Matrix10x16_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Matrix10x16_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -18432,20 +18265,20 @@ int _wrap_Matrix10x16_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mx int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix10x16_fillRowMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix1x6_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix10x16_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix1x6_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); } arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->fillRowMajorBuffer(arg2); + ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->fillRowMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -18454,8 +18287,8 @@ int _wrap_Matrix10x16_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mx } -int _wrap_Matrix10x16_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -18463,20 +18296,20 @@ int _wrap_Matrix10x16_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mx int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix10x16_fillColMajorBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix1x6_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix10x16_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix1x6_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); } arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->fillColMajorBuffer(arg2); + ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->fillColMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -18485,22 +18318,22 @@ int _wrap_Matrix10x16_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mx } -int _wrap_Matrix10x16_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Matrix10x16_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->toString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18509,22 +18342,22 @@ int _wrap_Matrix10x16_toString(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Matrix10x16_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Matrix10x16_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); - result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 1,6 > const *)arg1)->reservedToString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18533,22 +18366,22 @@ int _wrap_Matrix10x16_display(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Matrix10x16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Matrix10x16_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix1x6_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); - result = (mxArray *)iDynTree_MatrixFixSize_Sl_10_Sc_16_Sg__toMatlab((iDynTree::MatrixFixSize< 10,16 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_1_Sc_6_Sg__toMatlab((iDynTree::MatrixFixSize< 1,6 > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -18557,23 +18390,23 @@ int _wrap_Matrix10x16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Matrix10x16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_Matrix1x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Matrix10x16_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix1x6_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix1x6_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); arg2 = argv[1]; - iDynTree_MatrixFixSize_Sl_10_Sc_16_Sg__fromMatlab(arg1,arg2); + iDynTree_MatrixFixSize_Sl_1_Sc_6_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -18582,22 +18415,22 @@ int _wrap_Matrix10x16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_delete_Matrix10x16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; +int _wrap_delete_Matrix1x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 1,6 > *arg1 = (iDynTree::MatrixFixSize< 1,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Matrix10x16",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Matrix1x6",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_1_6_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix1x6" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 1,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 1,6 > * >(argp1); if (is_owned) { delete arg1; } @@ -18609,16 +18442,16 @@ int _wrap_delete_Matrix10x16(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Vector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix2x3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::VectorFixSize< 3 > *result = 0 ; + iDynTree::MatrixFixSize< 2,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector3",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Matrix2x3",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18626,31 +18459,39 @@ int _wrap_new_Vector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix2x3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 3 > *result = 0 ; + iDynTree::MatrixFixSize< 2,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector3",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix2x3",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector3" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector3" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix2x3" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix2x3" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18658,29 +18499,29 @@ int _wrap_new_Vector3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix2x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 3 > *result = 0 ; + iDynTree::MatrixFixSize< 2,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector3",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix2x3",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector3" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector3" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 2,3 > *)new iDynTree::MatrixFixSize< 2,3 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18688,20 +18529,20 @@ int _wrap_new_Vector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix2x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Vector3__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Matrix2x3__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Vector3__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Matrix2x3__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -18712,44 +18553,58 @@ int _wrap_new_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Vector3__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix2x3__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector3'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix2x3'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 3 >::VectorFixSize()\n" - " iDynTree::VectorFixSize< 3 >::VectorFixSize(double const *,std::size_t const)\n" - " iDynTree::VectorFixSize< 3 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 2,3 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Vector3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector3_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix2x3_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18758,30 +18613,38 @@ int _wrap_Vector3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector3_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix2x3_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -18790,11 +18653,11 @@ int _wrap_Vector3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Matrix2x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -18802,14 +18665,20 @@ int _wrap_Vector3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector3_paren__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix2x3_paren__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -18817,43 +18686,57 @@ int _wrap_Vector3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector3_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix2x3_paren__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix2x3_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 3 >::operator ()(std::size_t const) const\n" - " iDynTree::VectorFixSize< 3 >::operator ()(std::size_t const)\n"); + " iDynTree::MatrixFixSize< 2,3 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 2,3 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Vector3_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector3_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix2x3_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->operator [](arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -18862,31 +18745,47 @@ int _wrap_Vector3_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("Vector3_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix2x3_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix2x3_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix2x3_setVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix2x3_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18894,71 +18793,23 @@ int _wrap_Vector3_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector3_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector3_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 3 >::operator [](std::size_t const) const\n" - " iDynTree::VectorFixSize< 3 >::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_Vector3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - std::size_t arg2 ; +int _wrap_Matrix2x3_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::size_t result; - if (!SWIG_check_num_args("Vector3_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix2x3_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -18966,39 +18817,23 @@ int _wrap_Vector3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - std::size_t arg2 ; - double arg3 ; +int _wrap_Matrix2x3_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + std::size_t result; - if (!SWIG_check_num_args("Vector3_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix2x3_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector3_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19006,22 +18841,22 @@ int _wrap_Vector3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector3_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector3_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->begin(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -19030,23 +18865,22 @@ int _wrap_Vector3_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector3_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19054,23 +18888,30 @@ int _wrap_Vector3_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Vector3_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector3_cbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix2x3_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->fillRowMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19078,23 +18919,30 @@ int _wrap_Vector3_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector3_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector3_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix2x3_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->fillColMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19102,23 +18950,23 @@ int _wrap_Vector3_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector3_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("Vector3_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19126,51 +18974,23 @@ int _wrap_Vector3_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector3_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector3_begin__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector3_begin__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 3 >::begin() const\n" - " iDynTree::VectorFixSize< 3 >::begin()\n"); - return 1; -} - - -int _wrap_Vector3_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("Vector3_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)(arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 2,3 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19178,51 +18998,23 @@ int _wrap_Vector3_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Vector3_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector3_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector3_end__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 3 >::end() const\n" - " iDynTree::VectorFixSize< 3 >::end()\n"); - return 1; -} - - -int _wrap_Vector3_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("Vector3_size",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_2_Sc_3_Sg__toMatlab((iDynTree::MatrixFixSize< 2,3 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19230,173 +19022,23 @@ int _wrap_Vector3_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_Matrix2x3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector3_data",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix2x3_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix2x3_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector3_zero",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector3_fillBuffer",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector3_fillBuffer" "', argument " "2"" of type '" "double *""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorFixSize< 3 > const *)arg1)->fillBuffer(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Vector3_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Vector3_display",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - mxArray *result = 0 ; - - if (!SWIG_check_num_args("Vector3_toMatlab",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); - result = (mxArray *)iDynTree_VectorFixSize_Sl_3_Sg__toMatlab((iDynTree::VectorFixSize< 3 > const *)arg1); - _out = result; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector3_fromMatlab",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); arg2 = argv[1]; - iDynTree_VectorFixSize_Sl_3_Sg__fromMatlab(arg1,arg2); + iDynTree_MatrixFixSize_Sl_2_Sc_3_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -19405,22 +19047,22 @@ int _wrap_Vector3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_delete_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; +int _wrap_delete_Matrix2x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 2,3 > *arg1 = (iDynTree::MatrixFixSize< 2,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Vector3",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Matrix2x3",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_2_3_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector3" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix2x3" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 2,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 2,3 > * >(argp1); if (is_owned) { delete arg1; } @@ -19432,16 +19074,16 @@ int _wrap_delete_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_Vector4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix3x3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::VectorFixSize< 4 > *result = 0 ; + iDynTree::MatrixFixSize< 3,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector4",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Matrix3x3",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19449,31 +19091,39 @@ int _wrap_new_Vector4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix3x3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 4 > *result = 0 ; + iDynTree::MatrixFixSize< 3,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector4",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix3x3",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector4" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector4" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix3x3" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix3x3" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19481,29 +19131,29 @@ int _wrap_new_Vector4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix3x3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 4 > *result = 0 ; + iDynTree::MatrixFixSize< 3,3 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector4",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix3x3",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector4" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector4" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 3,3 > *)new iDynTree::MatrixFixSize< 3,3 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19511,20 +19161,20 @@ int _wrap_new_Vector4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix3x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Vector4__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Matrix3x3__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Vector4__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Matrix3x3__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -19535,44 +19185,58 @@ int _wrap_new_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Vector4__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix3x3__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector4'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix3x3'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 4 >::VectorFixSize()\n" - " iDynTree::VectorFixSize< 4 >::VectorFixSize(double const *,std::size_t const)\n" - " iDynTree::VectorFixSize< 4 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 3,3 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Vector4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector4_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -19581,30 +19245,38 @@ int _wrap_Vector4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector4_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -19613,11 +19285,11 @@ int _wrap_Vector4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Matrix3x3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -19625,14 +19297,20 @@ int _wrap_Vector4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector4_paren__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix3x3_paren__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -19640,43 +19318,57 @@ int _wrap_Vector4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector4_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix3x3_paren__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix3x3_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 4 >::operator ()(std::size_t const) const\n" - " iDynTree::VectorFixSize< 4 >::operator ()(std::size_t const)\n"); + " iDynTree::MatrixFixSize< 3,3 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 3,3 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Vector4_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector4_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->operator [](arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -19685,31 +19377,47 @@ int _wrap_Vector4_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector4_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("Vector4_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix3x3_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix3x3_setVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix3x3_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19717,71 +19425,23 @@ int _wrap_Vector4_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector4_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector4_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector4_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 4 >::operator [](std::size_t const) const\n" - " iDynTree::VectorFixSize< 4 >::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_Vector4_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - std::size_t arg2 ; +int _wrap_Matrix3x3_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::size_t result; - if (!SWIG_check_num_args("Vector4_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19789,39 +19449,23 @@ int _wrap_Vector4_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector4_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - std::size_t arg2 ; - double arg3 ; +int _wrap_Matrix3x3_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + std::size_t result; - if (!SWIG_check_num_args("Vector4_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix3x3_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector4_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -19829,22 +19473,22 @@ int _wrap_Vector4_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector4_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector4_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->begin(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -19853,199 +19497,22 @@ int _wrap_Vector4_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector4_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector4_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector4_cbegin",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector4_cend",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector4_begin",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector4_begin__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector4_begin__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 4 >::begin() const\n" - " iDynTree::VectorFixSize< 4 >::begin()\n"); - return 1; -} - - -int _wrap_Vector4_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector4_end",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)(arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector4_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector4_end__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 4 >::end() const\n" - " iDynTree::VectorFixSize< 4 >::end()\n"); - return 1; -} - - -int _wrap_Vector4_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("Vector4_size",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20053,45 +19520,29 @@ int _wrap_Vector4_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector4_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector4_data",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector4_zero",argc,1,1,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix3x3_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - (arg1)->zero(); + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->fillRowMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -20100,8 +19551,8 @@ int _wrap_Vector4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector4_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -20109,20 +19560,20 @@ int _wrap_Vector4_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[ int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector4_fillBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector4_fillBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix3x3_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); } arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorFixSize< 4 > const *)arg1)->fillBuffer(arg2); + ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->fillColMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -20131,22 +19582,22 @@ int _wrap_Vector4_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Vector4_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector4_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->toString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20155,22 +19606,22 @@ int _wrap_Vector4_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector4_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector4_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 3,3 > const *)arg1)->reservedToString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20179,22 +19630,22 @@ int _wrap_Vector4_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector4_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Vector4_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix3x3_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); - result = (mxArray *)iDynTree_VectorFixSize_Sl_4_Sg__toMatlab((iDynTree::VectorFixSize< 4 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_3_Sc_3_Sg__toMatlab((iDynTree::MatrixFixSize< 3,3 > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -20203,23 +19654,23 @@ int _wrap_Vector4_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector4_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_Matrix3x3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector4_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix3x3_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix3x3_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); arg2 = argv[1]; - iDynTree_VectorFixSize_Sl_4_Sg__fromMatlab(arg1,arg2); + iDynTree_MatrixFixSize_Sl_3_Sc_3_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -20228,22 +19679,22 @@ int _wrap_Vector4_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_delete_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; +int _wrap_delete_Matrix3x3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 3,3 > *arg1 = (iDynTree::MatrixFixSize< 3,3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Vector4",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Matrix3x3",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector4" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix3x3" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 3,3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 3,3 > * >(argp1); if (is_owned) { delete arg1; } @@ -20255,16 +19706,16 @@ int _wrap_delete_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_Vector6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix4x4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::VectorFixSize< 6 > *result = 0 ; + iDynTree::MatrixFixSize< 4,4 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector6",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Matrix4x4",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20272,31 +19723,39 @@ int _wrap_new_Vector6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix4x4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 6 > *result = 0 ; + iDynTree::MatrixFixSize< 4,4 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector6",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix4x4",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector6" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector6" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix4x4" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix4x4" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20304,29 +19763,29 @@ int _wrap_new_Vector6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix4x4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 6 > *result = 0 ; + iDynTree::MatrixFixSize< 4,4 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector6",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix4x4",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector6" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector6" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 4,4 > *)new iDynTree::MatrixFixSize< 4,4 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20334,20 +19793,20 @@ int _wrap_new_Vector6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix4x4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Vector6__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Matrix4x4__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Vector6__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Matrix4x4__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -20358,44 +19817,58 @@ int _wrap_new_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Vector6__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix4x4__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector6'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix4x4'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 6 >::VectorFixSize()\n" - " iDynTree::VectorFixSize< 6 >::VectorFixSize(double const *,std::size_t const)\n" - " iDynTree::VectorFixSize< 6 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 4,4 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Vector6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector6_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20404,30 +19877,38 @@ int _wrap_Vector6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector6_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -20436,11 +19917,11 @@ int _wrap_Vector6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Matrix4x4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -20448,14 +19929,20 @@ int _wrap_Vector6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector6_paren__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix4x4_paren__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -20463,43 +19950,57 @@ int _wrap_Vector6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector6_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix4x4_paren__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix4x4_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 6 >::operator ()(std::size_t const) const\n" - " iDynTree::VectorFixSize< 6 >::operator ()(std::size_t const)\n"); + " iDynTree::MatrixFixSize< 4,4 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 4,4 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Vector6_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector6_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->operator [](arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20508,142 +20009,46 @@ int _wrap_Vector6_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector6_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("Vector6_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix4x4_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector6_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector6_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 6 >::operator [](std::size_t const) const\n" - " iDynTree::VectorFixSize< 6 >::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_Vector6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - double result; - - if (!SWIG_check_num_args("Vector6_getVal",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - std::size_t arg2 ; - double arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Vector6_setVal",argc,3,3,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector6_setVal" "', argument " "3"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix4x4_setVal" "', argument " "3"" of type '" "std::size_t""'"); } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix4x4_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20652,95 +20057,23 @@ int _wrap_Vector6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector6_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector6_begin",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector6_end",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector6_cbegin",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::size_t result; - if (!SWIG_check_num_args("Vector6_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20748,23 +20081,23 @@ int _wrap_Vector6_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector6_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::size_t result; - if (!SWIG_check_num_args("Vector6_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20772,50 +20105,22 @@ int _wrap_Vector6_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Vector6_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector6_begin__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector6_begin__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 6 >::begin() const\n" - " iDynTree::VectorFixSize< 6 >::begin()\n"); - return 1; -} - - -int _wrap_Vector6_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector6_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)(arg1)->end(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -20824,51 +20129,22 @@ int _wrap_Vector6_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Vector6_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector6_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector6_end__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 6 >::end() const\n" - " iDynTree::VectorFixSize< 6 >::end()\n"); - return 1; -} - - -int _wrap_Vector6_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("Vector6_size",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -20876,45 +20152,29 @@ int _wrap_Vector6_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector6_data",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector6_zero",argc,1,1,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix4x4_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - (arg1)->zero(); + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->fillRowMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -20923,8 +20183,8 @@ int _wrap_Vector6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector6_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -20932,20 +20192,20 @@ int _wrap_Vector6_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[ int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector6_fillBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector6_fillBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix4x4_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); } arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorFixSize< 6 > const *)arg1)->fillBuffer(arg2); + ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->fillColMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -20954,22 +20214,22 @@ int _wrap_Vector6_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Vector6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector6_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->toString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -20978,22 +20238,22 @@ int _wrap_Vector6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector6_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 4,4 > const *)arg1)->reservedToString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -21002,22 +20262,22 @@ int _wrap_Vector6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Vector6_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix4x4_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); - result = (mxArray *)iDynTree_VectorFixSize_Sl_6_Sg__toMatlab((iDynTree::VectorFixSize< 6 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_4_Sc_4_Sg__toMatlab((iDynTree::MatrixFixSize< 4,4 > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -21026,23 +20286,23 @@ int _wrap_Vector6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_Matrix4x4_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector6_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix4x4_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix4x4_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); arg2 = argv[1]; - iDynTree_VectorFixSize_Sl_6_Sg__fromMatlab(arg1,arg2); + iDynTree_MatrixFixSize_Sl_4_Sc_4_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -21051,22 +20311,22 @@ int _wrap_Vector6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_delete_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; +int _wrap_delete_Matrix4x4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 4,4 > *arg1 = (iDynTree::MatrixFixSize< 4,4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Vector6",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Matrix4x4",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector6" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix4x4" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 4,4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 4,4 > * >(argp1); if (is_owned) { delete arg1; } @@ -21078,16 +20338,16 @@ int _wrap_delete_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_Vector10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix6x6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::VectorFixSize< 10 > *result = 0 ; + iDynTree::MatrixFixSize< 6,6 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector10",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Matrix6x6",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21095,31 +20355,39 @@ int _wrap_new_Vector10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Vector10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix6x6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 10 > *result = 0 ; + iDynTree::MatrixFixSize< 6,6 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector10",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix6x6",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector10" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector10" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix6x6" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix6x6" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21127,29 +20395,29 @@ int _wrap_new_Vector10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Vector10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix6x6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 10 > *result = 0 ; + iDynTree::MatrixFixSize< 6,6 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector10",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix6x6",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector10" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector10" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 6,6 > *)new iDynTree::MatrixFixSize< 6,6 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21157,20 +20425,20 @@ int _wrap_new_Vector10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Vector10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix6x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Vector10__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Matrix6x6__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Vector10__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Matrix6x6__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -21181,44 +20449,58 @@ int _wrap_new_Vector10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Vector10__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix6x6__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector10'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix6x6'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 10 >::VectorFixSize()\n" - " iDynTree::VectorFixSize< 10 >::VectorFixSize(double const *,std::size_t const)\n" - " iDynTree::VectorFixSize< 10 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 6,6 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Vector10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector10_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x6_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -21227,30 +20509,38 @@ int _wrap_Vector10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector10_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x6_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -21259,11 +20549,11 @@ int _wrap_Vector10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Matrix6x6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -21271,14 +20561,20 @@ int _wrap_Vector10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector10_paren__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix6x6_paren__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -21286,43 +20582,57 @@ int _wrap_Vector10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector10_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix6x6_paren__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix6x6_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 10 >::operator ()(std::size_t const) const\n" - " iDynTree::VectorFixSize< 10 >::operator ()(std::size_t const)\n"); + " iDynTree::MatrixFixSize< 6,6 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 6,6 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Vector10_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector10_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x6_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->operator [](arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -21331,31 +20641,47 @@ int _wrap_Vector10_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("Vector10_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x6_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x6_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x6_setVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix6x6_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21363,71 +20689,23 @@ int _wrap_Vector10_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector10_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector10_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 10 >::operator [](std::size_t const) const\n" - " iDynTree::VectorFixSize< 10 >::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_Vector10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - std::size_t arg2 ; +int _wrap_Matrix6x6_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::size_t result; - if (!SWIG_check_num_args("Vector10_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x6_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21435,39 +20713,23 @@ int _wrap_Vector10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - std::size_t arg2 ; - double arg3 ; +int _wrap_Matrix6x6_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + std::size_t result; - if (!SWIG_check_num_args("Vector10_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix6x6_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector10_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21475,22 +20737,22 @@ int _wrap_Vector10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector10_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector10_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->begin(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -21499,23 +20761,22 @@ int _wrap_Vector10_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector10_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21523,23 +20784,30 @@ int _wrap_Vector10_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Vector10_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector10_cbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x6_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->fillRowMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21547,23 +20815,30 @@ int _wrap_Vector10_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector10_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector10_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x6_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->fillColMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21571,23 +20846,23 @@ int _wrap_Vector10_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector10_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("Vector10_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21595,51 +20870,23 @@ int _wrap_Vector10_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector10_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector10_begin__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector10_begin__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 10 >::begin() const\n" - " iDynTree::VectorFixSize< 10 >::begin()\n"); - return 1; -} - - -int _wrap_Vector10_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("Vector10_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)(arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,6 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21647,51 +20894,23 @@ int _wrap_Vector10_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Vector10_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector10_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector10_end__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 10 >::end() const\n" - " iDynTree::VectorFixSize< 10 >::end()\n"); - return 1; -} - - -int _wrap_Vector10_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("Vector10_size",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_6_Sc_6_Sg__toMatlab((iDynTree::MatrixFixSize< 6,6 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21699,23 +20918,24 @@ int _wrap_Vector10_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_Matrix6x6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector10_data",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x6_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x6_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + arg2 = argv[1]; + iDynTree_MatrixFixSize_Sl_6_Sc_6_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21723,21 +20943,25 @@ int _wrap_Vector10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_delete_Matrix6x6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,6 > *arg1 = (iDynTree::MatrixFixSize< 6,6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector10_zero",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Matrix6x6",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix6x6" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,6 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,6 > * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -21746,30 +20970,16 @@ int _wrap_Vector10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Vector10_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; +int _wrap_new_Matrix6x10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::MatrixFixSize< 6,10 > *result = 0 ; - if (!SWIG_check_num_args("Vector10_fillBuffer",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix6x10",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector10_fillBuffer" "', argument " "2"" of type '" "double *""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorFixSize< 10 > const *)arg1)->fillBuffer(arg2); - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21777,172 +20987,39 @@ int _wrap_Vector10_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Vector10_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; +int _wrap_new_Matrix6x10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Vector10_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector10_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Vector10_display",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector10_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - mxArray *result = 0 ; - - if (!SWIG_check_num_args("Vector10_toMatlab",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - result = (mxArray *)iDynTree_VectorFixSize_Sl_10_Sg__toMatlab((iDynTree::VectorFixSize< 10 > const *)arg1); - _out = result; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector10_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector10_fromMatlab",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - arg2 = argv[1]; - iDynTree_VectorFixSize_Sl_10_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_delete_Vector10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - int is_owned; - if (!SWIG_check_num_args("delete_Vector10",argc,1,1,0)) { - SWIG_fail; - } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector10" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Vector16__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::VectorFixSize< 16 > *result = 0 ; - - if (!SWIG_check_num_args("new_Vector16",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Vector16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - iDynTree::VectorFixSize< 16 > *result = 0 ; + iDynTree::MatrixFixSize< 6,10 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector16",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix6x10",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector16" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector16" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix6x10" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix6x10" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21950,29 +21027,29 @@ int _wrap_new_Vector16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Vector16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix6x10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::VectorFixSize< 16 > *result = 0 ; + iDynTree::MatrixFixSize< 6,10 > *result = 0 ; - if (!SWIG_check_num_args("new_Vector16",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix6x10",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector16" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector16" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 6,10 > *)new iDynTree::MatrixFixSize< 6,10 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -21980,20 +21057,20 @@ int _wrap_new_Vector16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Vector16__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Matrix6x10__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Vector16__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Matrix6x10__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); @@ -22004,44 +21081,58 @@ int _wrap_new_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_Vector16__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Matrix6x10__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector16'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix6x10'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 16 >::VectorFixSize()\n" - " iDynTree::VectorFixSize< 16 >::VectorFixSize(double const *,std::size_t const)\n" - " iDynTree::VectorFixSize< 16 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 6,10 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_Vector16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector16_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->operator ()(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -22050,30 +21141,38 @@ int _wrap_Vector16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector16_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_paren" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_paren" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator ()(arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -22082,11 +21181,11 @@ int _wrap_Vector16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Matrix6x10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -22094,14 +21193,20 @@ int _wrap_Vector16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector16_paren__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix6x10_paren__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0); _v = SWIG_CheckState(res); if (_v) { { @@ -22109,43 +21214,57 @@ int _wrap_Vector16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - return _wrap_Vector16_paren__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix6x10_paren__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix6x10_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 16 >::operator ()(std::size_t const) const\n" - " iDynTree::VectorFixSize< 16 >::operator ()(std::size_t const)\n"); + " iDynTree::MatrixFixSize< 6,10 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 6,10 >::operator ()(std::size_t const,std::size_t const)\n"); return 1; } -int _wrap_Vector16_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("Vector16_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_getVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->operator [](arg2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->getVal(arg2,arg3); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -22154,31 +21273,47 @@ int _wrap_Vector16_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector16_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - double *result = 0 ; + bool result; - if (!SWIG_check_num_args("Vector16_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_brace" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix6x10_setVal" "', argument " "2"" of type '" "std::size_t""'"); } arg2 = static_cast< std::size_t >(val2); - result = (double *) &(arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix6x10_setVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix6x10_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22186,71 +21321,23 @@ int _wrap_Vector16_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector16_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector16_brace__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Vector16_brace__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_brace'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 16 >::operator [](std::size_t const) const\n" - " iDynTree::VectorFixSize< 16 >::operator [](std::size_t const)\n"); - return 1; -} - - -int _wrap_Vector16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - std::size_t arg2 ; +int _wrap_Matrix6x10_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::size_t result; - if (!SWIG_check_num_args("Vector16_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_getVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22258,39 +21345,23 @@ int _wrap_Vector16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - std::size_t arg2 ; - double arg3 ; +int _wrap_Matrix6x10_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + std::size_t result; - if (!SWIG_check_num_args("Vector16_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix6x10_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_setVal" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector16_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22298,22 +21369,22 @@ int _wrap_Vector16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector16_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; double *result = 0 ; - if (!SWIG_check_num_args("Vector16_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->begin(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = (double *)(arg1)->data(); _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -22322,23 +21393,22 @@ int _wrap_Vector16_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Vector16_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector16_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22346,23 +21416,30 @@ int _wrap_Vector16_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Vector16_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector16_cbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_fillRowMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x10_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->fillRowMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22370,228 +21447,29 @@ int _wrap_Vector16_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector16_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - double *result = 0 ; - if (!SWIG_check_num_args("Vector16_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector16_begin",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)(arg1)->begin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector16_begin__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector16_begin__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_begin'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 16 >::begin() const\n" - " iDynTree::VectorFixSize< 16 >::begin()\n"); - return 1; -} - - -int _wrap_Vector16_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector16_end",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)(arg1)->end(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector16_end__SWIG_1(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Vector16_end__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_end'." - " Possible C/C++ prototypes are:\n" - " iDynTree::VectorFixSize< 16 >::end() const\n" - " iDynTree::VectorFixSize< 16 >::end()\n"); - return 1; -} - - -int _wrap_Vector16_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t result; - - if (!SWIG_check_num_args("Vector16_size",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - double *result = 0 ; - - if (!SWIG_check_num_args("Vector16_data",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (double *)(arg1)->data(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector16_zero",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Vector16_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; - double *arg2 = (double *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Vector16_fillBuffer",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector16_fillBuffer" "', argument " "2"" of type '" "double *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix6x10_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); } arg2 = reinterpret_cast< double * >(argp2); - ((iDynTree::VectorFixSize< 16 > const *)arg1)->fillBuffer(arg2); + ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->fillColMajorBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -22600,22 +21478,22 @@ int _wrap_Vector16_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Vector16_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector16_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->toString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -22624,22 +21502,22 @@ int _wrap_Vector16_toString(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Vector16_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Vector16_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 6,10 > const *)arg1)->reservedToString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -22648,22 +21526,22 @@ int _wrap_Vector16_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Vector16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; mxArray *result = 0 ; - if (!SWIG_check_num_args("Vector16_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix6x10_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); - result = (mxArray *)iDynTree_VectorFixSize_Sl_16_Sg__toMatlab((iDynTree::VectorFixSize< 16 > const *)arg1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_6_Sc_10_Sg__toMatlab((iDynTree::MatrixFixSize< 6,10 > const *)arg1); _out = result; if (_out) --resc, *resv++ = _out; return 0; @@ -22672,23 +21550,23 @@ int _wrap_Vector16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Vector16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_Matrix6x10_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Vector16_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix6x10_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix6x10_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); arg2 = argv[1]; - iDynTree_VectorFixSize_Sl_16_Sg__fromMatlab(arg1,arg2); + iDynTree_MatrixFixSize_Sl_6_Sc_10_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -22697,22 +21575,22 @@ int _wrap_Vector16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_delete_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; +int _wrap_delete_Matrix6x10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 6,10 > *arg1 = (iDynTree::MatrixFixSize< 6,10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Vector16",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Matrix6x10",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector16" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix6x10" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 6,10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 6,10 > * >(argp1); if (is_owned) { delete arg1; } @@ -22724,56 +21602,16 @@ int _wrap_delete_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_PositionRaw__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix10x16__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::PositionRaw *result = 0 ; + iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_PositionRaw",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Matrix10x16",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::PositionRaw *)new iDynTree::PositionRaw(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_PositionRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - iDynTree::PositionRaw *result = 0 ; - - if (!SWIG_check_num_args("new_PositionRaw",argc,3,3,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_PositionRaw" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_PositionRaw" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_PositionRaw" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (iDynTree::PositionRaw *)new iDynTree::PositionRaw(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22781,58 +21619,39 @@ int _wrap_new_PositionRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_PositionRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix10x16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; - unsigned int arg2 ; + std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; + size_t val2 ; int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::PositionRaw *result = 0 ; + iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_PositionRaw",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Matrix10x16",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_PositionRaw" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_PositionRaw" "', argument " "2"" of type '" "unsigned int""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Matrix10x16" "', argument " "2"" of type '" "std::size_t""'"); } - arg2 = static_cast< unsigned int >(val2); - result = (iDynTree::PositionRaw *)new iDynTree::PositionRaw((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_PositionRaw__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::PositionRaw *result = 0 ; - - if (!SWIG_check_num_args("new_PositionRaw",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_PositionRaw" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_PositionRaw" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - result = (iDynTree::PositionRaw *)new iDynTree::PositionRaw((iDynTree::PositionRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 1 | 0 ); + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Matrix10x16" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22840,29 +21659,29 @@ int _wrap_new_PositionRaw__SWIG_3(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_PositionRaw__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; +int _wrap_new_Matrix10x16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::PositionRaw *result = 0 ; + iDynTree::MatrixFixSize< 10,16 > *result = 0 ; - if (!SWIG_check_num_args("new_PositionRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Matrix10x16",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_PositionRaw" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_PositionRaw" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); } } - result = (iDynTree::PositionRaw *)new iDynTree::PositionRaw(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 1 | 0 ); + result = (iDynTree::MatrixFixSize< 10,16 > *)new iDynTree::MatrixFixSize< 10,16 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22870,105 +21689,83 @@ int _wrap_new_PositionRaw__SWIG_4(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_PositionRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Matrix10x16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_PositionRaw__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_PositionRaw__SWIG_3(resc,resv,argc,argv); - } + return _wrap_new_Matrix10x16__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_PositionRaw__SWIG_4(resc,resv,argc,argv); + return _wrap_new_Matrix10x16__SWIG_2(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_PositionRaw__SWIG_2(resc,resv,argc,argv); - } - } - } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); + int res = SWIG_AsVal_size_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { { - int res = SWIG_AsVal_double(argv[2], NULL); + int res = SWIG_AsVal_size_t(argv[2], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_PositionRaw__SWIG_1(resc,resv,argc,argv); + return _wrap_new_Matrix10x16__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_PositionRaw'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Matrix10x16'." " Possible C/C++ prototypes are:\n" - " iDynTree::PositionRaw::PositionRaw()\n" - " iDynTree::PositionRaw::PositionRaw(double,double,double)\n" - " iDynTree::PositionRaw::PositionRaw(double const *,unsigned int const)\n" - " iDynTree::PositionRaw::PositionRaw(iDynTree::PositionRaw const &)\n" - " iDynTree::PositionRaw::PositionRaw(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize()\n" + " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize(double const *,std::size_t const,std::size_t const)\n" + " iDynTree::MatrixFixSize< 10,16 >::MatrixFixSize(iDynTree::MatrixView< double const >)\n"); return 1; } -int _wrap_PositionRaw_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; - iDynTree::PositionRaw *arg2 = 0 ; +int _wrap_Matrix10x16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::PositionRaw *result = 0 ; + double result; - if (!SWIG_check_num_args("PositionRaw_changePoint",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix10x16_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_changePoint" "', argument " "1"" of type '" "iDynTree::PositionRaw *""'"); - } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "PositionRaw_changePoint" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_changePoint" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - result = (iDynTree::PositionRaw *) &(arg1)->changePoint((iDynTree::PositionRaw const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->operator ()(arg2,arg3); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -22976,34 +21773,39 @@ int _wrap_PositionRaw_changePoint(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_PositionRaw_changeRefPoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; - iDynTree::PositionRaw *arg2 = 0 ; +int _wrap_Matrix10x16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::PositionRaw *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("PositionRaw_changeRefPoint",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix10x16_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_changeRefPoint" "', argument " "1"" of type '" "iDynTree::PositionRaw *""'"); - } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "PositionRaw_changeRefPoint" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_changeRefPoint" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_paren" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - result = (iDynTree::PositionRaw *) &(arg1)->changeRefPoint((iDynTree::PositionRaw const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_paren" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double *) &(arg1)->operator ()(arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23011,64 +21813,91 @@ int _wrap_PositionRaw_changeRefPoint(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_PositionRaw_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = 0 ; - iDynTree::PositionRaw *arg2 = 0 ; - void *argp1 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::PositionRaw result; - - if (!SWIG_check_num_args("PositionRaw_compose",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_compose" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_compose" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "PositionRaw_compose" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_compose" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); +int _wrap_Matrix10x16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix10x16_paren__SWIG_0(resc,resv,argc,argv); + } + } + } } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - result = iDynTree::PositionRaw::compose((iDynTree::PositionRaw const &)*arg1,(iDynTree::PositionRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::PositionRaw(static_cast< const iDynTree::PositionRaw& >(result))), SWIGTYPE_p_iDynTree__PositionRaw, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_PositionRaw_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = 0 ; - void *argp1 ; + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Matrix10x16_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Matrix10x16_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::MatrixFixSize< 10,16 >::operator ()(std::size_t const,std::size_t const) const\n" + " iDynTree::MatrixFixSize< 10,16 >::operator ()(std::size_t const,std::size_t const)\n"); + return 1; +} + + +int _wrap_Matrix10x16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::PositionRaw result; + double result; - if (!SWIG_check_num_args("PositionRaw_inverse",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix10x16_getVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_inverse" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_inverse" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_getVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - result = iDynTree::PositionRaw::inverse((iDynTree::PositionRaw const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::PositionRaw(static_cast< const iDynTree::PositionRaw& >(result))), SWIGTYPE_p_iDynTree__PositionRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_getVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (double)((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->getVal(arg2,arg3); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23076,34 +21905,71 @@ int _wrap_PositionRaw_inverse(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_PositionRaw_changePointOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_Matrix10x16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + std::size_t arg2 ; + std::size_t arg3 ; + double arg4 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + bool result; - if (!SWIG_check_num_args("PositionRaw_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix10x16_setVal",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_changePointOf" "', argument " "1"" of type '" "iDynTree::PositionRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_setVal" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "PositionRaw_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Matrix10x16_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Matrix10x16_setVal" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Matrix10x16_setVal" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = (bool)(arg1)->setVal(arg2,arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Matrix10x16_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("Matrix10x16_rows",argc,1,1,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_rows" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::PositionRaw const *)arg1)->changePointOf((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->rows(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23111,34 +21977,47 @@ int _wrap_PositionRaw_changePointOf__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_PositionRaw_changePointOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Matrix10x16_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + std::size_t result; - if (!SWIG_check_num_args("PositionRaw_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Matrix10x16_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_changePointOf" "', argument " "1"" of type '" "iDynTree::PositionRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_cols" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "PositionRaw_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->cols(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Matrix10x16_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + double *result = 0 ; + + if (!SWIG_check_num_args("Matrix10x16_data",argc,1,1,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PositionRaw_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_data" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::PositionRaw const *)arg1)->changePointOf((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23146,61 +22025,84 @@ int _wrap_PositionRaw_changePointOf__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_PositionRaw_changePointOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_PositionRaw_changePointOf__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_Matrix10x16_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("Matrix10x16_zero",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_PositionRaw_changePointOf__SWIG_1(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_zero" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); } + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Matrix10x16_fillRowMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + double *arg2 = (double *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'PositionRaw_changePointOf'." - " Possible C/C++ prototypes are:\n" - " iDynTree::PositionRaw::changePointOf(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::PositionRaw::changePointOf(iDynTree::SpatialForceVector const &) const\n"); + if (!SWIG_check_num_args("Matrix10x16_fillRowMajorBuffer",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fillRowMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix10x16_fillRowMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->fillRowMajorBuffer(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_PositionRaw_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; +int _wrap_Matrix10x16_fillColMajorBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("PositionRaw_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix10x16_fillColMajorBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_toString" "', argument " "1"" of type '" "iDynTree::PositionRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fillColMajorBuffer" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - result = ((iDynTree::PositionRaw const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Matrix10x16_fillColMajorBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->fillColMajorBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23208,22 +22110,22 @@ int _wrap_PositionRaw_toString(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_PositionRaw_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; +int _wrap_Matrix10x16_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("PositionRaw_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix10x16_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PositionRaw_display" "', argument " "1"" of type '" "iDynTree::PositionRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_toString" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - result = ((iDynTree::PositionRaw const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -23232,26 +22134,23 @@ int _wrap_PositionRaw_display(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_delete_PositionRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = (iDynTree::PositionRaw *) 0 ; +int _wrap_Matrix10x16_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::string result; - int is_owned; - if (!SWIG_check_num_args("delete_PositionRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("Matrix10x16_display",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PositionRaw, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_PositionRaw" "', argument " "1"" of type '" "iDynTree::PositionRaw *""'"); - } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_display" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = ((iDynTree::MatrixFixSize< 10,16 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23259,16 +22158,23 @@ int _wrap_delete_PositionRaw(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Position__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Matrix10x16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + mxArray *result = 0 ; - if (!SWIG_check_num_args("new_Position",argc,0,0,0)) { + if (!SWIG_check_num_args("Matrix10x16_toMatlab",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Position *)new iDynTree::Position(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_toMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + result = (mxArray *)iDynTree_MatrixFixSize_Sl_10_Sc_16_Sg__toMatlab((iDynTree::MatrixFixSize< 10,16 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23276,39 +22182,24 @@ int _wrap_new_Position__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Position__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_Matrix10x16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_Position",argc,3,3,0)) { + if (!SWIG_check_num_args("Matrix10x16_fromMatlab",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Position" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Position" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Position" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (iDynTree::Position *)new iDynTree::Position(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Matrix10x16_fromMatlab" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + arg2 = argv[1]; + iDynTree_MatrixFixSize_Sl_10_Sc_16_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23316,26 +22207,26 @@ int _wrap_new_Position__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Position__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = 0 ; - void *argp1 ; +int _wrap_delete_Matrix10x16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixFixSize< 10,16 > *arg1 = (iDynTree::MatrixFixSize< 10,16 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_Position",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Matrix10x16",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Matrix10x16" "', argument " "1"" of type '" "iDynTree::MatrixFixSize< 10,16 > *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Position const &""'"); + arg1 = reinterpret_cast< iDynTree::MatrixFixSize< 10,16 > * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - result = (iDynTree::Position *)new iDynTree::Position((iDynTree::Position const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23343,26 +22234,48 @@ int _wrap_new_Position__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Position__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::PositionRaw *arg1 = 0 ; - void *argp1 ; +int _wrap_new_Vector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::VectorFixSize< 3 > *result = 0 ; + + if (!SWIG_check_num_args("new_Vector3",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Vector3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::VectorFixSize< 3 > *result = 0 ; - if (!SWIG_check_num_args("new_Position",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Vector3",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector3" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::PositionRaw * >(argp1); - result = (iDynTree::Position *)new iDynTree::Position((iDynTree::PositionRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector3" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23370,29 +22283,29 @@ int _wrap_new_Position__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Position__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::VectorFixSize< 3 > *result = 0 ; - if (!SWIG_check_num_args("new_Position",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Vector3",argc,1,1,0)) { SWIG_fail; } { res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector3" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector3" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } else { arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); } } - result = (iDynTree::Position *)new iDynTree::Position(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); + result = (iDynTree::VectorFixSize< 3 > *)new iDynTree::VectorFixSize< 3 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23400,99 +22313,69 @@ int _wrap_new_Position__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Position(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Position__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Position__SWIG_2(resc,resv,argc,argv); - } + return _wrap_new_Vector3__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Position__SWIG_3(resc,resv,argc,argv); + return _wrap_new_Vector3__SWIG_2(resc,resv,argc,argv); } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Position__SWIG_4(resc,resv,argc,argv); - } - } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } if (_v) { { - int res = SWIG_AsVal_double(argv[1], NULL); + int res = SWIG_AsVal_size_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_double(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Position__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_Vector3__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Position'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector3'." " Possible C/C++ prototypes are:\n" - " iDynTree::Position::Position()\n" - " iDynTree::Position::Position(double,double,double)\n" - " iDynTree::Position::Position(iDynTree::Position const &)\n" - " iDynTree::Position::Position(iDynTree::PositionRaw const &)\n" - " iDynTree::Position::Position(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::VectorFixSize< 3 >::VectorFixSize()\n" + " iDynTree::VectorFixSize< 3 >::VectorFixSize(double const *,std::size_t const)\n" + " iDynTree::VectorFixSize< 3 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_Position_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_Vector3_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + double result; - if (!SWIG_check_num_args("Position_changePoint",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePoint" "', argument " "1"" of type '" "iDynTree::Position *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (iDynTree::Position *) &(arg1)->changePoint((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->operator ()(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23500,34 +22383,31 @@ int _wrap_Position_changePoint(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Position_changeRefPoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_Vector3_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changeRefPoint",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changeRefPoint" "', argument " "1"" of type '" "iDynTree::Position *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changeRefPoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changeRefPoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (iDynTree::Position *) &(arg1)->changeRefPoint((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23535,34 +22415,71 @@ int _wrap_Position_changeRefPoint(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Vector3_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector3_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector3_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 3 >::operator ()(std::size_t const) const\n" + " iDynTree::VectorFixSize< 3 >::operator ()(std::size_t const)\n"); + return 1; +} + + +int _wrap_Vector3_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + double result; - if (!SWIG_check_num_args("Position_changeCoordinateFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changeCoordinateFrame" "', argument " "1"" of type '" "iDynTree::Position *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (iDynTree::Position *) &(arg1)->changeCoordinateFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->operator [](arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23570,37 +22487,31 @@ int _wrap_Position_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector3_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_compose" "', argument " "1"" of type '" "iDynTree::Position const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_compose" "', argument " "1"" of type '" "iDynTree::Position const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_compose" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_compose" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = iDynTree::Position::compose((iDynTree::Position const &)*arg1,(iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23608,26 +22519,71 @@ int _wrap_Position_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Position_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector3_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector3_brace__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector3_brace__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_brace'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 3 >::operator [](std::size_t const) const\n" + " iDynTree::VectorFixSize< 3 >::operator [](std::size_t const)\n"); + return 1; +} + + +int _wrap_Vector3_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position result; + double result; - if (!SWIG_check_num_args("Position_inverse",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector3_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_inverse" "', argument " "1"" of type '" "iDynTree::Position const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_inverse" "', argument " "1"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - result = iDynTree::Position::inverse((iDynTree::Position const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 3 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23635,34 +22591,39 @@ int _wrap_Position_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Position_changePointOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_Vector3_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + bool result; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector3_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector3_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23670,34 +22631,23 @@ int _wrap_Position_changePointOf__SWIG_0(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Vector3_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23705,34 +22655,23 @@ int _wrap_Position_changePointOf__SWIG_1(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Vector3_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Twist result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23740,34 +22679,23 @@ int _wrap_Position_changePointOf__SWIG_2(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_Vector3_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_cbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23775,34 +22703,23 @@ int _wrap_Position_changePointOf__SWIG_3(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_Vector3_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_cend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 3 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23810,34 +22727,23 @@ int _wrap_Position_changePointOf__SWIG_4(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_Vector3_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -23845,191 +22751,103 @@ int _wrap_Position_changePointOf__SWIG_5(int resc, mxArray *resv[], int argc, mx } -int _wrap_Position_changePointOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Vector3_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_2(resc,resv,argc,argv); - } + return _wrap_Vector3_begin__SWIG_1(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_4(resc,resv,argc,argv); - } + return _wrap_Vector3_begin__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_3(resc,resv,argc,argv); - } - } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 3 >::begin() const\n" + " iDynTree::VectorFixSize< 3 >::begin()\n"); + return 1; +} + + +int _wrap_Vector3_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + double *result = 0 ; + + if (!SWIG_check_num_args("Vector3_end",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_0(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - if (argc == 2) { + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Vector3_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_5(resc,resv,argc,argv); - } + return _wrap_Vector3_end__SWIG_1(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_changePointOf__SWIG_1(resc,resv,argc,argv); - } + return _wrap_Vector3_end__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Position_changePointOf'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector3_end'." " Possible C/C++ prototypes are:\n" - " iDynTree::Position::changePointOf(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::Position::changePointOf(iDynTree::SpatialForceVector const &) const\n" - " iDynTree::Position::changePointOf(iDynTree::Twist const &) const\n" - " iDynTree::Position::changePointOf(iDynTree::SpatialAcc const &) const\n" - " iDynTree::Position::changePointOf(iDynTree::SpatialMomentum const &) const\n" - " iDynTree::Position::changePointOf(iDynTree::Wrench const &) const\n"); - return 1; -} - - -int _wrap_Position_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::Position result; - - if (!SWIG_check_num_args("Position_plus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_plus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_plus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_plus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator +((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Position_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::Position result; - - if (!SWIG_check_num_args("Position_minus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_minus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_minus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_minus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator -((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::VectorFixSize< 3 >::end() const\n" + " iDynTree::VectorFixSize< 3 >::end()\n"); return 1; } -int _wrap_Position_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; +int _wrap_Vector3_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Position result; + std::size_t result; - if (!SWIG_check_num_args("Position_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector3_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_uminus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - result = ((iDynTree::Position const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24037,34 +22855,23 @@ int _wrap_Position_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Position_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Vector3_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Twist result; + double *result = 0 ; - if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24072,34 +22879,22 @@ int _wrap_Position_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Vector3_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24107,34 +22902,30 @@ int _wrap_Position_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_Vector3_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_fillBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector3_fillBuffer" "', argument " "2"" of type '" "double *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorFixSize< 3 > const *)arg1)->fillBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24142,34 +22933,23 @@ int _wrap_Position_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_Vector3_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + std::string result; - if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24177,34 +22957,23 @@ int _wrap_Position_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_Vector3_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + std::string result; - if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector3_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = ((iDynTree::VectorFixSize< 3 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24212,106 +22981,23 @@ int _wrap_Position_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Position_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_mtimes__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_mtimes__SWIG_3(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_mtimes__SWIG_2(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_mtimes__SWIG_4(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Position_mtimes__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Position_mtimes'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Position::operator *(iDynTree::Twist const &) const\n" - " iDynTree::Position::operator *(iDynTree::SpatialForceVector const &) const\n" - " iDynTree::Position::operator *(iDynTree::SpatialAcc const &) const\n" - " iDynTree::Position::operator *(iDynTree::SpatialMomentum const &) const\n" - " iDynTree::Position::operator *(iDynTree::Wrench const &) const\n"); - return 1; -} - - -int _wrap_Position_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; +int _wrap_Vector3_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("Position_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector3_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_toString" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - result = ((iDynTree::Position const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + result = (mxArray *)iDynTree_VectorFixSize_Sl_3_Sg__toMatlab((iDynTree::VectorFixSize< 3 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24319,40 +23005,24 @@ int _wrap_Position_toString(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Position_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; +int _wrap_Vector3_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("Position_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector3_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_display" "', argument " "1"" of type '" "iDynTree::Position const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); - result = ((iDynTree::Position const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Position_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::Position result; - - if (!SWIG_check_num_args("Position_Zero",argc,0,0,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector3_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - (void)argv; - result = iDynTree::Position::Zero(); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); + arg2 = argv[1]; + iDynTree_VectorFixSize_Sl_3_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24360,22 +23030,22 @@ int _wrap_Position_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Position(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; +int _wrap_delete_Vector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 3 > *arg1 = (iDynTree::VectorFixSize< 3 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Position",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Vector3",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Position" "', argument " "1"" of type '" "iDynTree::Position *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector3" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 3 > *""'"); } - arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 3 > * >(argp1); if (is_owned) { delete arg1; } @@ -24387,16 +23057,16 @@ int _wrap_delete_Position(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_GeomVector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector4__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::GeomVector3 *result = 0 ; + iDynTree::VectorFixSize< 4 > *result = 0 ; - if (!SWIG_check_num_args("new_GeomVector3",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Vector4",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); + result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24404,71 +23074,31 @@ int _wrap_new_GeomVector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_GeomVector3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector4__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double *arg1 = (double *) 0 ; - unsigned int arg2 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; + size_t val2 ; int ecode2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 *result = 0 ; + iDynTree::VectorFixSize< 4 > *result = 0 ; - if (!SWIG_check_num_args("new_GeomVector3",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector4",argc,2,2,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector4" "', argument " "1"" of type '" "double const *""'"); } arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_GeomVector3" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_GeomVector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - iDynTree::GeomVector3 *result = 0 ; - - if (!SWIG_check_num_args("new_GeomVector3",argc,3,3,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_GeomVector3" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_GeomVector3" "', argument " "3"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector4" "', argument " "2"" of type '" "std::size_t""'"); } - arg3 = static_cast< double >(val3); - result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); + arg2 = static_cast< std::size_t >(val2); + result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24476,29 +23106,29 @@ int _wrap_new_GeomVector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_GeomVector3__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Vector3 arg1 ; +int _wrap_new_Vector4__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::GeomVector3 *result = 0 ; + iDynTree::VectorFixSize< 4 > *result = 0 ; - if (!SWIG_check_num_args("new_GeomVector3",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Vector4",argc,1,1,0)) { SWIG_fail; } { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "iDynTree::Vector3 const""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector4" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_GeomVector3" "', argument " "1"" of type '" "iDynTree::Vector3 const""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector4" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); } else { - arg1 = *(reinterpret_cast< iDynTree::Vector3 * >(argp1)); + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); } } - result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); + result = (iDynTree::VectorFixSize< 4 > *)new iDynTree::VectorFixSize< 4 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24506,17 +23136,17 @@ int _wrap_new_GeomVector3__SWIG_3(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_GeomVector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_GeomVector3__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Vector4__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_GeomVector3__SWIG_3(resc,resv,argc,argv); + return _wrap_new_Vector4__SWIG_2(resc,resv,argc,argv); } } if (argc == 2) { @@ -24526,75 +23156,49 @@ int _wrap_new_GeomVector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + int res = SWIG_AsVal_size_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_GeomVector3__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_GeomVector3__SWIG_2(resc,resv,argc,argv); - } + return _wrap_new_Vector4__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_GeomVector3'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector4'." " Possible C/C++ prototypes are:\n" - " iDynTree::GeomVector3::GeomVector3()\n" - " iDynTree::GeomVector3::GeomVector3(double const *,unsigned int const)\n" - " iDynTree::GeomVector3::GeomVector3(double const,double const,double const)\n" - " iDynTree::GeomVector3::GeomVector3(iDynTree::Vector3 const)\n"); + " iDynTree::VectorFixSize< 4 >::VectorFixSize()\n" + " iDynTree::VectorFixSize< 4 >::VectorFixSize(double const *,std::size_t const)\n" + " iDynTree::VectorFixSize< 4 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_GeomVector3_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Vector4_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 result; + double result; - if (!SWIG_check_num_args("GeomVector3_changeCoordFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = ((iDynTree::GeomVector3 const *)arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->operator ()(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24602,45 +23206,31 @@ int _wrap_GeomVector3_changeCoordFrame(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_GeomVector3_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; - iDynTree::GeomVector3 *arg3 = 0 ; +int _wrap_Vector4_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 result; + double *result = 0 ; - if (!SWIG_check_num_args("GeomVector3_compose",argc,3,3,0)) { + if (!SWIG_check_num_args("Vector4_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_compose" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_compose" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_compose" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); - } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "GeomVector3_compose" "', argument " "3"" of type '" "iDynTree::GeomVector3 const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_compose" "', argument " "3"" of type '" "iDynTree::GeomVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg3 = reinterpret_cast< iDynTree::GeomVector3 * >(argp3); - result = ((iDynTree::GeomVector3 const *)arg1)->compose((iDynTree::GeomVector3 const &)*arg2,(iDynTree::GeomVector3 const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24648,68 +23238,70 @@ int _wrap_GeomVector3_compose(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_GeomVector3_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::GeomVector3 result; - - if (!SWIG_check_num_args("GeomVector3_inverse",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_inverse" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_inverse" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); +int _wrap_Vector4_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector4_paren__SWIG_0(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_inverse" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector4_paren__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - result = ((iDynTree::GeomVector3 const *)arg1)->inverse((iDynTree::GeomVector3 const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 4 >::operator ()(std::size_t const) const\n" + " iDynTree::VectorFixSize< 4 >::operator ()(std::size_t const)\n"); return 1; } -int _wrap_GeomVector3_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; +int _wrap_Vector4_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("GeomVector3_dot",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_dot" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_dot" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_dot" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - result = (double)((iDynTree::GeomVector3 const *)arg1)->dot((iDynTree::GeomVector3 const &)*arg2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->operator [](arg2); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -24718,34 +23310,31 @@ int _wrap_GeomVector3_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_GeomVector3_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; +int _wrap_Vector4_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 result; + double *result = 0 ; - if (!SWIG_check_num_args("GeomVector3_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_plus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_plus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_plus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - result = ((iDynTree::GeomVector3 const *)arg1)->operator +((iDynTree::GeomVector3 const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24753,58 +23342,71 @@ int _wrap_GeomVector3_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_GeomVector3_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::GeomVector3 result; - - if (!SWIG_check_num_args("GeomVector3_minus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_minus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_minus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); +int _wrap_Vector4_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector4_brace__SWIG_0(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_minus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector4_brace__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - result = ((iDynTree::GeomVector3 const *)arg1)->operator -((iDynTree::GeomVector3 const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_brace'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 4 >::operator [](std::size_t const) const\n" + " iDynTree::VectorFixSize< 4 >::operator [](std::size_t const)\n"); return 1; } -int _wrap_GeomVector3_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; +int _wrap_Vector4_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 result; + double result; - if (!SWIG_check_num_args("GeomVector3_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_uminus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - result = ((iDynTree::GeomVector3 const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 4 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24812,23 +23414,39 @@ int _wrap_GeomVector3_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_GeomVector3_exp(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; +int _wrap_Vector4_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Rotation result; + bool result; - if (!SWIG_check_num_args("GeomVector3_exp",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_exp" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - result = ((iDynTree::GeomVector3 const *)arg1)->exp(); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector4_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector4_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24836,34 +23454,23 @@ int _wrap_GeomVector3_exp(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_GeomVector3_cross(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; - iDynTree::GeomVector3 *arg2 = 0 ; +int _wrap_Vector4_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::GeomVector3 result; + double *result = 0 ; - if (!SWIG_check_num_args("GeomVector3_cross",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_cross" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_cross" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_cross" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); - result = ((iDynTree::GeomVector3 const *)arg1)->cross((iDynTree::GeomVector3 const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24871,43 +23478,23 @@ int _wrap_GeomVector3_cross(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_GeomVector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; +int _wrap_Vector4_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_GeomVector3",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_end",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_GeomVector3" "', argument " "1"" of type '" "iDynTree::GeomVector3 *""'"); - } - arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_SpatialMotionVectorBase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; - - if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,0,0,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - (void)argv; - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24915,37 +23502,23 @@ int _wrap_new_SpatialMotionVectorBase__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_new_SpatialMotionVectorBase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *arg1 = 0 ; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector4_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_cbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMotionVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T * >(argp2); - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &)*arg1,(iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24953,26 +23526,23 @@ int _wrap_new_SpatialMotionVectorBase__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_new_SpatialMotionVectorBase__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector4_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_cend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 4 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -24980,29 +23550,23 @@ int _wrap_new_SpatialMotionVectorBase__SWIG_2(int resc, mxArray *resv[], int arg } -int _wrap_new_SpatialMotionVectorBase__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; - void *argp1 ; +int _wrap_Vector4_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_begin",argc,1,1,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25010,70 +23574,103 @@ int _wrap_new_SpatialMotionVectorBase__SWIG_3(int resc, mxArray *resv[], int arg } -int _wrap_new_SpatialMotionVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SpatialMotionVectorBase__SWIG_0(resc,resv,argc,argv); - } +int _wrap_Vector4_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialMotionVectorBase__SWIG_2(resc,resv,argc,argv); + return _wrap_Vector4_begin__SWIG_1(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialMotionVectorBase__SWIG_3(resc,resv,argc,argv); + return _wrap_Vector4_begin__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 4 >::begin() const\n" + " iDynTree::VectorFixSize< 4 >::begin()\n"); + return 1; +} + + +int _wrap_Vector4_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + double *result = 0 ; + + if (!SWIG_check_num_args("Vector4_end",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Vector4_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMotionVectorBase__SWIG_1(resc,resv,argc,argv); - } + return _wrap_Vector4_end__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector4_end__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMotionVectorBase'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector4_end'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector()\n" - " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &,iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)\n" - " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)\n" - " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::VectorFixSize< 4 >::end() const\n" + " iDynTree::VectorFixSize< 4 >::end()\n"); return 1; } -int _wrap_SpatialMotionVectorBase_getLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector4_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *result = 0 ; + std::size_t result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_getLinearVec3",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *) &(arg1)->getLinearVec3(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25081,23 +23678,23 @@ int _wrap_SpatialMotionVectorBase_getLinearVec3(int resc, mxArray *resv[], int a } -int _wrap_SpatialMotionVectorBase_getAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector4_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_getAngularVec3",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *) &(arg1)->getAngularVec3(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25105,32 +23702,21 @@ int _wrap_SpatialMotionVectorBase_getAngularVec3(int resc, mxArray *resv[], int } -int _wrap_SpatialMotionVectorBase_setLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *arg2 = 0 ; +int _wrap_Vector4_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialMotionVectorBase_setLinearVec3",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T * >(argp2); - (arg1)->setLinearVec3((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &)*arg2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -25139,32 +23725,29 @@ int _wrap_SpatialMotionVectorBase_setLinearVec3(int resc, mxArray *resv[], int a } -int _wrap_SpatialMotionVectorBase_setAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *arg2 = 0 ; +int _wrap_Vector4_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialMotionVectorBase_setAngularVec3",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_fillBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector4_fillBuffer" "', argument " "2"" of type '" "double *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T * >(argp2); - (arg1)->setAngularVec3((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)*arg2); + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorFixSize< 4 > const *)arg1)->fillBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -25173,31 +23756,23 @@ int _wrap_SpatialMotionVectorBase_setAngularVec3(int resc, mxArray *resv[], int } -int _wrap_SpatialMotionVectorBase_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - unsigned int arg2 ; +int _wrap_Vector4_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_paren" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_paren" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (double *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25205,31 +23780,23 @@ int _wrap_SpatialMotionVectorBase_paren(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialMotionVectorBase_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - unsigned int arg2 ; +int _wrap_Vector4_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::string result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector4_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_getVal" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (double)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = ((iDynTree::VectorFixSize< 4 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25237,39 +23804,23 @@ int _wrap_SpatialMotionVectorBase_getVal(int resc, mxArray *resv[], int argc, mx } -int _wrap_SpatialMotionVectorBase_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - unsigned int arg2 ; - double arg3 ; +int _wrap_Vector4_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Vector4_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + result = (mxArray *)iDynTree_VectorFixSize_Sl_4_Sg__toMatlab((iDynTree::VectorFixSize< 4 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25277,23 +23828,24 @@ int _wrap_SpatialMotionVectorBase_setVal(int resc, mxArray *resv[], int argc, mx } -int _wrap_SpatialMotionVectorBase_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector4_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - unsigned int result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_size",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector4_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_size" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector4_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (unsigned int)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->size(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + arg2 = argv[1]; + iDynTree_VectorFixSize_Sl_4_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25301,21 +23853,25 @@ int _wrap_SpatialMotionVectorBase_size(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SpatialMotionVectorBase_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_delete_Vector4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 4 > *arg1 = (iDynTree::VectorFixSize< 4 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialMotionVectorBase_zero",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Vector4",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_zero" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector4" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 4 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 4 > * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -25324,34 +23880,16 @@ int _wrap_SpatialMotionVectorBase_zero(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SpatialMotionVectorBase_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_Vector6__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialMotionVector result; + iDynTree::VectorFixSize< 6 > *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_changePoint",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector6",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (arg1)->changePoint((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25359,34 +23897,31 @@ int _wrap_SpatialMotionVectorBase_changePoint(int resc, mxArray *resv[], int arg } -int _wrap_SpatialMotionVectorBase_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_new_Vector6__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + iDynTree::VectorFixSize< 6 > *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_changeCoordFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector6",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector6" "', argument " "1"" of type '" "double const *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector6" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25394,37 +23929,29 @@ int _wrap_SpatialMotionVectorBase_changeCoordFrame(int resc, mxArray *resv[], in } -int _wrap_SpatialMotionVectorBase_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_new_Vector6__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + iDynTree::VectorFixSize< 6 > *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector6",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector6" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector6" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR compose((iDynTree::SpatialMotionVector const &)*arg1,(iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + result = (iDynTree::VectorFixSize< 6 > *)new iDynTree::VectorFixSize< 6 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25432,60 +23959,68 @@ int _wrap_SpatialMotionVectorBase_compose(int resc, mxArray *resv[], int argc, m } -int _wrap_SpatialMotionVectorBase_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialMotionVector result; - - if (!SWIG_check_num_args("SpatialMotionVectorBase_inverse",argc,1,1,0)) { - SWIG_fail; +int _wrap_new_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Vector6__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Vector6__SWIG_2(resc,resv,argc,argv); + } } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Vector6__SWIG_1(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR inverse((iDynTree::SpatialMotionVector const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector6'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 6 >::VectorFixSize()\n" + " iDynTree::VectorFixSize< 6 >::VectorFixSize(double const *,std::size_t const)\n" + " iDynTree::VectorFixSize< 6 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_SpatialMotionVectorBase_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT *arg2 = 0 ; +int _wrap_Vector6_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_dot",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_dot" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT * >(argp2); - result = (double)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->dot((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &)*arg2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->operator ()(arg2); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -25494,34 +24029,31 @@ int _wrap_SpatialMotionVectorBase_dot(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialMotionVectorBase_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_Vector6_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_plus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator +((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25529,58 +24061,71 @@ int _wrap_SpatialMotionVectorBase_plus(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SpatialMotionVectorBase_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::SpatialMotionVector result; - - if (!SWIG_check_num_args("SpatialMotionVectorBase_minus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_minus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); +int _wrap_Vector6_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector6_paren__SWIG_0(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector6_paren__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator -((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 6 >::operator ()(std::size_t const) const\n" + " iDynTree::VectorFixSize< 6 >::operator ()(std::size_t const)\n"); return 1; } -int _wrap_SpatialMotionVectorBase_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector6_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + double result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_uminus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->operator [](arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25588,16 +24133,31 @@ int _wrap_SpatialMotionVectorBase_uminus(int resc, mxArray *resv[], int argc, mx } -int _wrap_SpatialMotionVectorBase_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector6_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_Zero",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector6_brace",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR Zero(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25605,47 +24165,71 @@ int _wrap_SpatialMotionVectorBase_Zero(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SpatialMotionVectorBase_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Vector6 result; - - if (!SWIG_check_num_args("SpatialMotionVectorBase_asVector",argc,1,1,0)) { - SWIG_fail; +int _wrap_Vector6_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector6_brace__SWIG_0(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_asVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector6_brace__SWIG_1(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->asVector(); - _out = SWIG_NewPointerObj((new iDynTree::Vector6(static_cast< const iDynTree::Vector6& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_brace'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 6 >::operator [](std::size_t const) const\n" + " iDynTree::VectorFixSize< 6 >::operator [](std::size_t const)\n"); return 1; } -int _wrap_SpatialMotionVectorBase_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector6_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::string result; + double result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_toString" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 6 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25653,23 +24237,39 @@ int _wrap_SpatialMotionVectorBase_toString(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialMotionVectorBase_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector6_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("SpatialMotionVectorBase_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_display" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector6_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector6_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25677,23 +24277,23 @@ int _wrap_SpatialMotionVectorBase_display(int resc, mxArray *resv[], int argc, m } -int _wrap_SpatialMotionVectorBase_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector6_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - mxArray *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_toMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (mxArray *)iDynTree_SpatialVector_Sl_iDynTree_SpatialMotionVector_Sg__toMatlab((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1); - _out = result; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25701,24 +24301,23 @@ int _wrap_SpatialMotionVectorBase_toMatlab(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialMotionVectorBase_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_Vector6_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVectorBase_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_fromMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - arg2 = argv[1]; - iDynTree_SpatialVector_Sl_iDynTree_SpatialMotionVector_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25726,26 +24325,23 @@ int _wrap_SpatialMotionVectorBase_fromMatlab(int resc, mxArray *resv[], int argc } -int _wrap_delete_SpatialMotionVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; +int _wrap_Vector6_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialMotionVectorBase",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_cbegin",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25753,16 +24349,23 @@ int _wrap_delete_SpatialMotionVectorBase(int resc, mxArray *resv[], int argc, mx } -int _wrap_new_SpatialForceVectorBase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector6_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector6_cend",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 6 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25770,37 +24373,23 @@ int _wrap_new_SpatialForceVectorBase__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_new_SpatialForceVectorBase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *arg1 = 0 ; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector6_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialForceVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T * >(argp2); - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &)*arg1,(iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25808,56 +24397,51 @@ int _wrap_new_SpatialForceVectorBase__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_new_SpatialForceVectorBase__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; - - if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); +int _wrap_Vector6_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector6_begin__SWIG_1(resc,resv,argc,argv); + } } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector6_begin__SWIG_0(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 6 >::begin() const\n" + " iDynTree::VectorFixSize< 6 >::begin()\n"); return 1; } -int _wrap_new_SpatialForceVectorBase__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; - void *argp1 ; +int _wrap_Vector6_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_end",argc,1,1,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25865,70 +24449,51 @@ int _wrap_new_SpatialForceVectorBase__SWIG_3(int resc, mxArray *resv[], int argc } -int _wrap_new_SpatialForceVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SpatialForceVectorBase__SWIG_0(resc,resv,argc,argv); - } +int _wrap_Vector6_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialForceVectorBase__SWIG_2(resc,resv,argc,argv); + return _wrap_Vector6_end__SWIG_1(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialForceVectorBase__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialForceVectorBase__SWIG_1(resc,resv,argc,argv); - } + return _wrap_Vector6_end__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialForceVectorBase'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector6_end'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector()\n" - " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &,iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)\n" - " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)\n" - " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::Span< double const,-1 >)\n"); + " iDynTree::VectorFixSize< 6 >::end() const\n" + " iDynTree::VectorFixSize< 6 >::end()\n"); return 1; } -int _wrap_SpatialForceVectorBase_getLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector6_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *result = 0 ; + std::size_t result; - if (!SWIG_check_num_args("SpatialForceVectorBase_getLinearVec3",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *) &(arg1)->getLinearVec3(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25936,23 +24501,23 @@ int _wrap_SpatialForceVectorBase_getLinearVec3(int resc, mxArray *resv[], int ar } -int _wrap_SpatialForceVectorBase_getAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector6_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_getAngularVec3",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *) &(arg1)->getAngularVec3(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -25960,32 +24525,21 @@ int _wrap_SpatialForceVectorBase_getAngularVec3(int resc, mxArray *resv[], int a } -int _wrap_SpatialForceVectorBase_setLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *arg2 = 0 ; +int _wrap_Vector6_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialForceVectorBase_setLinearVec3",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T * >(argp2); - (arg1)->setLinearVec3((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &)*arg2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -25994,32 +24548,29 @@ int _wrap_SpatialForceVectorBase_setLinearVec3(int resc, mxArray *resv[], int ar } -int _wrap_SpatialForceVectorBase_setAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *arg2 = 0 ; +int _wrap_Vector6_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialForceVectorBase_setAngularVec3",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_fillBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector6_fillBuffer" "', argument " "2"" of type '" "double *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T * >(argp2); - (arg1)->setAngularVec3((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)*arg2); + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorFixSize< 6 > const *)arg1)->fillBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -26028,31 +24579,23 @@ int _wrap_SpatialForceVectorBase_setAngularVec3(int resc, mxArray *resv[], int a } -int _wrap_SpatialForceVectorBase_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - unsigned int arg2 ; +int _wrap_Vector6_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; mxArray * _out; - double *result = 0 ; + std::string result; - if (!SWIG_check_num_args("SpatialForceVectorBase_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_paren" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_paren" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (double *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26060,31 +24603,23 @@ int _wrap_SpatialForceVectorBase_paren(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SpatialForceVectorBase_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - unsigned int arg2 ; +int _wrap_Vector6_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + std::string result; - if (!SWIG_check_num_args("SpatialForceVectorBase_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector6_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_getVal" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (double)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = ((iDynTree::VectorFixSize< 6 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26092,39 +24627,23 @@ int _wrap_SpatialForceVectorBase_getVal(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialForceVectorBase_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - unsigned int arg2 ; - double arg3 ; +int _wrap_Vector6_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + mxArray *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Vector6_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_setVal" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SpatialForceVectorBase_setVal" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)(arg1)->setVal(arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + result = (mxArray *)iDynTree_VectorFixSize_Sl_6_Sg__toMatlab((iDynTree::VectorFixSize< 6 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26132,23 +24651,24 @@ int _wrap_SpatialForceVectorBase_setVal(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialForceVectorBase_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector6_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - unsigned int result; - if (!SWIG_check_num_args("SpatialForceVectorBase_size",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector6_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_size" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector6_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (unsigned int)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->size(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + arg2 = argv[1]; + iDynTree_VectorFixSize_Sl_6_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26156,21 +24676,25 @@ int _wrap_SpatialForceVectorBase_size(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialForceVectorBase_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_delete_Vector6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 6 > *arg1 = (iDynTree::VectorFixSize< 6 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialForceVectorBase_zero",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Vector6",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_zero" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector6" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 6 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 6 > * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -26179,34 +24703,16 @@ int _wrap_SpatialForceVectorBase_zero(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialForceVectorBase_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_Vector10__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::VectorFixSize< 10 > *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_changePoint",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector10",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_changePoint" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (arg1)->changePoint((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26214,34 +24720,31 @@ int _wrap_SpatialForceVectorBase_changePoint(int resc, mxArray *resv[], int argc } -int _wrap_SpatialForceVectorBase_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_new_Vector10__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::VectorFixSize< 10 > *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_changeCoordFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector10",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector10" "', argument " "1"" of type '" "double const *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector10" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26249,37 +24752,29 @@ int _wrap_SpatialForceVectorBase_changeCoordFrame(int resc, mxArray *resv[], int } -int _wrap_SpatialForceVectorBase_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_new_Vector10__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::VectorFixSize< 10 > *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Vector10",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector10" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector10" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR compose((iDynTree::SpatialForceVector const &)*arg1,(iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + result = (iDynTree::VectorFixSize< 10 > *)new iDynTree::VectorFixSize< 10 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26287,60 +24782,68 @@ int _wrap_SpatialForceVectorBase_compose(int resc, mxArray *resv[], int argc, mx } -int _wrap_SpatialForceVectorBase_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialForceVector result; - - if (!SWIG_check_num_args("SpatialForceVectorBase_inverse",argc,1,1,0)) { - SWIG_fail; +int _wrap_new_Vector10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Vector10__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Vector10__SWIG_2(resc,resv,argc,argv); + } } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Vector10__SWIG_1(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR inverse((iDynTree::SpatialForceVector const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector10'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 10 >::VectorFixSize()\n" + " iDynTree::VectorFixSize< 10 >::VectorFixSize(double const *,std::size_t const)\n" + " iDynTree::VectorFixSize< 10 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_SpatialForceVectorBase_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT *arg2 = 0 ; +int _wrap_Vector10_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; double result; - if (!SWIG_check_num_args("SpatialForceVectorBase_dot",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_dot" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT * >(argp2); - result = (double)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->dot((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &)*arg2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->operator ()(arg2); _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -26349,34 +24852,31 @@ int _wrap_SpatialForceVectorBase_dot(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SpatialForceVectorBase_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Vector10_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_plus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator +((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26384,75 +24884,71 @@ int _wrap_SpatialForceVectorBase_plus(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialForceVectorBase_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::SpatialForceVector result; - - if (!SWIG_check_num_args("SpatialForceVectorBase_minus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_minus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); +int _wrap_Vector10_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector10_paren__SWIG_0(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector10_paren__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator -((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 10 >::operator ()(std::size_t const) const\n" + " iDynTree::VectorFixSize< 10 >::operator ()(std::size_t const)\n"); return 1; } -int _wrap_SpatialForceVectorBase_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector10_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + double result; - if (!SWIG_check_num_args("SpatialForceVectorBase_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_uminus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SpatialForceVectorBase_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::SpatialForceVector result; - - if (!SWIG_check_num_args("SpatialForceVectorBase_Zero",argc,0,0,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - (void)argv; - result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR Zero(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->operator [](arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26460,23 +24956,31 @@ int _wrap_SpatialForceVectorBase_Zero(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialForceVectorBase_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector10_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Vector6 result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_asVector",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_asVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->asVector(); - _out = SWIG_NewPointerObj((new iDynTree::Vector6(static_cast< const iDynTree::Vector6& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26484,47 +24988,71 @@ int _wrap_SpatialForceVectorBase_asVector(int resc, mxArray *resv[], int argc, m } -int _wrap_SpatialForceVectorBase_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("SpatialForceVectorBase_toString",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_toString" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); +int _wrap_Vector10_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector10_brace__SWIG_0(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector10_brace__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_brace'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 10 >::operator [](std::size_t const) const\n" + " iDynTree::VectorFixSize< 10 >::operator [](std::size_t const)\n"); return 1; } -int _wrap_SpatialForceVectorBase_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector10_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::string result; + double result; - if (!SWIG_check_num_args("SpatialForceVectorBase_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_display" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 10 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26532,23 +25060,39 @@ int _wrap_SpatialForceVectorBase_display(int resc, mxArray *resv[], int argc, mx } -int _wrap_SpatialForceVectorBase_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector10_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - mxArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("SpatialForceVectorBase_toMatlab",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_toMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (mxArray *)iDynTree_SpatialVector_Sl_iDynTree_SpatialForceVector_Sg__toMatlab((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1); - _out = result; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector10_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector10_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26556,24 +25100,23 @@ int _wrap_SpatialForceVectorBase_toMatlab(int resc, mxArray *resv[], int argc, m } -int _wrap_SpatialForceVectorBase_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; - mxArray *arg2 = (mxArray *) 0 ; +int _wrap_Vector10_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVectorBase_fromMatlab",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_fromMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - arg2 = argv[1]; - iDynTree_SpatialVector_Sl_iDynTree_SpatialForceVector_Sg__fromMatlab(arg1,arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26581,43 +25124,23 @@ int _wrap_SpatialForceVectorBase_fromMatlab(int resc, mxArray *resv[], int argc, } -int _wrap_delete_SpatialForceVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; +int _wrap_Vector10_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialForceVectorBase",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_end",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::Dummy *result = 0 ; - - if (!SWIG_check_num_args("new_Dummy",argc,0,0,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - (void)argv; - result = (iDynTree::Dummy *)new iDynTree::Dummy(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Dummy, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26625,26 +25148,23 @@ int _wrap_new_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Dummy *arg1 = (iDynTree::Dummy *) 0 ; +int _wrap_Vector10_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_Dummy",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_cbegin",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Dummy, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Dummy" "', argument " "1"" of type '" "iDynTree::Dummy *""'"); - } - arg1 = reinterpret_cast< iDynTree::Dummy * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26652,16 +25172,23 @@ int _wrap_delete_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_SpatialMotionVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector10_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVector",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector10_cend",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 10 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26669,37 +25196,23 @@ int _wrap_new_SpatialMotionVector__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SpatialMotionVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinearMotionVector3 *arg1 = 0 ; - iDynTree::AngularMotionVector3 *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector10_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVector",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::LinearMotionVector3 const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::LinearMotionVector3 const &""'"); - } - arg1 = reinterpret_cast< iDynTree::LinearMotionVector3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMotionVector" "', argument " "2"" of type '" "iDynTree::AngularMotionVector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "2"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg2 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp2); - result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::LinearMotionVector3 const &)*arg1,(iDynTree::AngularMotionVector3 const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26707,53 +25220,51 @@ int _wrap_new_SpatialMotionVector__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SpatialMotionVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; - - if (!SWIG_check_num_args("new_SpatialMotionVector",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); +int _wrap_Vector10_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector10_begin__SWIG_1(resc,resv,argc,argv); + } } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector10_begin__SWIG_0(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::SpatialMotionVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 10 >::begin() const\n" + " iDynTree::VectorFixSize< 10 >::begin()\n"); return 1; } -int _wrap_new_SpatialMotionVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector10_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMotionVector",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); - result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26761,78 +25272,51 @@ int _wrap_new_SpatialMotionVector__SWIG_3(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SpatialMotionVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SpatialMotionVector__SWIG_0(resc,resv,argc,argv); - } +int _wrap_Vector10_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialMotionVector__SWIG_2(resc,resv,argc,argv); + return _wrap_Vector10_end__SWIG_1(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMotionVector__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMotionVector__SWIG_1(resc,resv,argc,argv); - } + return _wrap_Vector10_end__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMotionVector'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector10_end'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialMotionVector::SpatialMotionVector()\n" - " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::LinearMotionVector3 const &,iDynTree::AngularMotionVector3 const &)\n" - " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::SpatialMotionVector const &)\n" - " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)\n"); + " iDynTree::VectorFixSize< 10 >::end() const\n" + " iDynTree::VectorFixSize< 10 >::end()\n"); return 1; } -int _wrap_SpatialMotionVector_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; - double arg2 ; +int _wrap_Vector10_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + std::size_t result; - if (!SWIG_check_num_args("SpatialMotionVector_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVector_mtimes" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::SpatialMotionVector const *)arg1)->operator *(arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26840,34 +25324,23 @@ int _wrap_SpatialMotionVector_mtimes(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SpatialMotionVector_cross__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_Vector10_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialMotionVector_cross",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_cross" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::SpatialMotionVector const *)arg1)->cross((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26875,34 +25348,22 @@ int _wrap_SpatialMotionVector_cross__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialMotionVector_cross__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Vector10_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialMotionVector_cross",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector10_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_cross" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::SpatialMotionVector const *)arg1)->cross((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26910,61 +25371,30 @@ int _wrap_SpatialMotionVector_cross__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialMotionVector_cross(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SpatialMotionVector_cross__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SpatialMotionVector_cross__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SpatialMotionVector_cross'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialMotionVector::cross(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::SpatialMotionVector::cross(iDynTree::SpatialForceVector const &) const\n"); - return 1; -} - - -int _wrap_SpatialMotionVector_asCrossProductMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; +int _wrap_Vector10_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("SpatialMotionVector_asCrossProductMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_fillBuffer",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_asCrossProductMatrix" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = ((iDynTree::SpatialMotionVector const *)arg1)->asCrossProductMatrix(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector10_fillBuffer" "', argument " "2"" of type '" "double *""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorFixSize< 10 > const *)arg1)->fillBuffer(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26972,23 +25402,23 @@ int _wrap_SpatialMotionVector_asCrossProductMatrix(int resc, mxArray *resv[], in } -int _wrap_SpatialMotionVector_asCrossProductMatrixWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; +int _wrap_Vector10_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; + std::string result; - if (!SWIG_check_num_args("SpatialMotionVector_asCrossProductMatrixWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_asCrossProductMatrixWrench" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = ((iDynTree::SpatialMotionVector const *)arg1)->asCrossProductMatrixWrench(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -26996,23 +25426,23 @@ int _wrap_SpatialMotionVector_asCrossProductMatrixWrench(int resc, mxArray *resv } -int _wrap_SpatialMotionVector_exp(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; +int _wrap_Vector10_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform result; + std::string result; - if (!SWIG_check_num_args("SpatialMotionVector_exp",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_exp" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = ((iDynTree::SpatialMotionVector const *)arg1)->exp(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = ((iDynTree::VectorFixSize< 10 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27020,26 +25450,23 @@ int _wrap_SpatialMotionVector_exp(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_delete_SpatialMotionVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; +int _wrap_Vector10_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + mxArray *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialMotionVector",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector10_toMatlab",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + result = (mxArray *)iDynTree_VectorFixSize_Sl_10_Sg__toMatlab((iDynTree::VectorFixSize< 10 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27047,16 +25474,24 @@ int _wrap_delete_SpatialMotionVector(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_SpatialForceVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector10_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVector",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector10_fromMatlab",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector10_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + arg2 = argv[1]; + iDynTree_VectorFixSize_Sl_10_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27064,37 +25499,43 @@ int _wrap_new_SpatialForceVector__SWIG_0(int resc, mxArray *resv[], int argc, mx } -int _wrap_new_SpatialForceVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector::LinearVector3T *arg1 = 0 ; - iDynTree::SpatialForceVector::AngularVector3T *arg2 = 0 ; - void *argp1 ; +int _wrap_delete_Vector10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 10 > *arg1 = (iDynTree::VectorFixSize< 10 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVector",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Vector10",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector::LinearVector3T const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector::LinearVector3T const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector10" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 10 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector::LinearVector3T * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialForceVector" "', argument " "2"" of type '" "iDynTree::SpatialForceVector::AngularVector3T const &""'"); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 10 > * >(argp1); + if (is_owned) { + delete arg1; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "2"" of type '" "iDynTree::SpatialForceVector::AngularVector3T const &""'"); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Vector16__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::VectorFixSize< 16 > *result = 0 ; + + if (!SWIG_check_num_args("new_Vector16",argc,0,0,0)) { + SWIG_fail; } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector::AngularVector3T * >(argp2); - result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialForceVector::LinearVector3T const &)*arg1,(iDynTree::SpatialForceVector::AngularVector3T const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); + (void)argv; + result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27102,26 +25543,31 @@ int _wrap_new_SpatialForceVector__SWIG_1(int resc, mxArray *resv[], int argc, mx } -int _wrap_new_SpatialForceVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - void *argp1 ; +int _wrap_new_Vector16__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; + iDynTree::VectorFixSize< 16 > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVector",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Vector16",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector16" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialForceVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Vector16" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27129,26 +25575,29 @@ int _wrap_new_SpatialForceVector__SWIG_2(int resc, mxArray *resv[], int argc, mx } -int _wrap_new_SpatialForceVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = 0 ; +int _wrap_new_Vector16__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; + iDynTree::VectorFixSize< 16 > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialForceVector",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Vector16",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Vector16" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Vector16" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); - result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); + result = (iDynTree::VectorFixSize< 16 > *)new iDynTree::VectorFixSize< 16 >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27156,73 +25605,69 @@ int _wrap_new_SpatialForceVector__SWIG_3(int resc, mxArray *resv[], int argc, mx } -int _wrap_new_SpatialForceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_SpatialForceVector__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialForceVector__SWIG_2(resc,resv,argc,argv); - } + return _wrap_new_Vector16__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialForceVector__SWIG_3(resc,resv,argc,argv); + return _wrap_new_Vector16__SWIG_2(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_SpatialForceVector__SWIG_1(resc,resv,argc,argv); + return _wrap_new_Vector16__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialForceVector'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Vector16'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialForceVector::SpatialForceVector()\n" - " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialForceVector::LinearVector3T const &,iDynTree::SpatialForceVector::AngularVector3T const &)\n" - " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialForceVector const &)\n" - " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)\n"); + " iDynTree::VectorFixSize< 16 >::VectorFixSize()\n" + " iDynTree::VectorFixSize< 16 >::VectorFixSize(double const *,std::size_t const)\n" + " iDynTree::VectorFixSize< 16 >::VectorFixSize(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_delete_SpatialForceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = (iDynTree::SpatialForceVector *) 0 ; +int _wrap_Vector16_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; + double result; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialForceVector",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_paren",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_paren" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->operator ()(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27230,48 +25675,31 @@ int _wrap_delete_SpatialForceVector(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialForceVector_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = (iDynTree::SpatialForceVector *) 0 ; - double arg2 ; +int _wrap_Vector16_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; + size_t val2 ; int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialForceVector_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVector_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_paren" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVector_mtimes" "', argument " "2"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_paren" "', argument " "2"" of type '" "std::size_t""'"); } - arg2 = static_cast< double >(val2); - result = ((iDynTree::SpatialForceVector const *)arg1)->operator *(arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Twist__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::Twist *result = 0 ; - - if (!SWIG_check_num_args("new_Twist",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::Twist *)new iDynTree::Twist(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27279,64 +25707,71 @@ int _wrap_new_Twist__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_Twist__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinVelocity *arg1 = 0 ; - iDynTree::AngVelocity *arg2 = 0 ; - void *argp1 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::Twist *result = 0 ; - - if (!SWIG_check_num_args("new_Twist",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::LinVelocity const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::LinVelocity const &""'"); - } - arg1 = reinterpret_cast< iDynTree::LinVelocity * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Twist" "', argument " "2"" of type '" "iDynTree::AngVelocity const &""'"); +int _wrap_Vector16_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector16_paren__SWIG_0(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "2"" of type '" "iDynTree::AngVelocity const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector16_paren__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::AngVelocity * >(argp2); - result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::LinVelocity const &)*arg1,(iDynTree::AngVelocity const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 16 >::operator ()(std::size_t const) const\n" + " iDynTree::VectorFixSize< 16 >::operator ()(std::size_t const)\n"); return 1; } -int _wrap_new_Twist__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector16_brace__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Twist *result = 0 ; + double result; - if (!SWIG_check_num_args("new_Twist",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::SpatialMotionVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->operator [](arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27344,26 +25779,31 @@ int _wrap_new_Twist__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_Twist__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector16_brace__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Twist *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_Twist",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_brace" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::Twist const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_brace" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double *) &(arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27371,81 +25811,71 @@ int _wrap_new_Twist__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_Twist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Twist__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Twist__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 1) { +int _wrap_Vector16_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Twist__SWIG_2(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Vector16_brace__SWIG_0(resc,resv,argc,argv); + } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_Twist__SWIG_1(resc,resv,argc,argv); + return _wrap_Vector16_brace__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Twist'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_brace'." " Possible C/C++ prototypes are:\n" - " iDynTree::Twist::Twist()\n" - " iDynTree::Twist::Twist(iDynTree::LinVelocity const &,iDynTree::AngVelocity const &)\n" - " iDynTree::Twist::Twist(iDynTree::SpatialMotionVector const &)\n" - " iDynTree::Twist::Twist(iDynTree::Twist const &)\n"); + " iDynTree::VectorFixSize< 16 >::operator [](std::size_t const) const\n" + " iDynTree::VectorFixSize< 16 >::operator [](std::size_t const)\n"); return 1; } -int _wrap_Twist_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Vector16_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Twist result; + double result; - if (!SWIG_check_num_args("Twist_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_plus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_plus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_plus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_getVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Twist const *)arg1)->operator +((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_getVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + result = (double)((iDynTree::VectorFixSize< 16 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27453,58 +25883,39 @@ int _wrap_Twist_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Twist_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Vector16_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + std::size_t arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Twist result; + bool result; - if (!SWIG_check_num_args("Twist_minus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_minus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_minus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_minus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_setVal" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Twist const *)arg1)->operator -((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Twist_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Twist result; - - if (!SWIG_check_num_args("Twist_uminus",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_uminus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - result = ((iDynTree::Twist const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Vector16_setVal" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Vector16_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27512,34 +25923,23 @@ int _wrap_Twist_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Twist_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Vector16_begin__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + double *result = 0 ; - if (!SWIG_check_num_args("Twist_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_mtimes" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Twist const *)arg1)->operator *((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27547,34 +25947,23 @@ int _wrap_Twist_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Twist_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_Vector16_end__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + double *result = 0 ; - if (!SWIG_check_num_args("Twist_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_mtimes" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Twist const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27582,64 +25971,23 @@ int _wrap_Twist_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Twist_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Twist_mtimes__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Twist_mtimes__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Twist_mtimes'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Twist::operator *(iDynTree::Twist const &) const\n" - " iDynTree::Twist::operator *(iDynTree::SpatialMomentum const &) const\n"); - return 1; -} - - -int _wrap_delete_Twist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; +int _wrap_Vector16_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + double *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_Twist",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_cbegin",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Twist" "', argument " "1"" of type '" "iDynTree::Twist *""'"); - } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_cbegin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27647,16 +25995,23 @@ int _wrap_delete_Twist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_Wrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector16_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_Wrench",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector16_cend",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Wrench *)new iDynTree::Wrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_cend" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)((iDynTree::VectorFixSize< 16 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27664,37 +26019,23 @@ int _wrap_new_Wrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Wrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Force *arg1 = 0 ; - iDynTree::Torque *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector16_begin__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_Wrench",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Force const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Force const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Force * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Wrench" "', argument " "2"" of type '" "iDynTree::Torque const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "2"" of type '" "iDynTree::Torque const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_begin" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Torque * >(argp2); - result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::Force const &)*arg1,(iDynTree::Torque const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)(arg1)->begin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27702,53 +26043,51 @@ int _wrap_new_Wrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Wrench__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Wrench *result = 0 ; - - if (!SWIG_check_num_args("new_Wrench",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); +int _wrap_Vector16_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector16_begin__SWIG_1(resc,resv,argc,argv); + } } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Vector16_begin__SWIG_0(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::SpatialForceVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_begin'." + " Possible C/C++ prototypes are:\n" + " iDynTree::VectorFixSize< 16 >::begin() const\n" + " iDynTree::VectorFixSize< 16 >::begin()\n"); return 1; } -int _wrap_new_Wrench__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Wrench *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector16_end__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_Wrench",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Wrench, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_end" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); - result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::Wrench const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)(arg1)->end(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27756,81 +26095,51 @@ int _wrap_new_Wrench__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Wrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Wrench__SWIG_0(resc,resv,argc,argv); - } +int _wrap_Vector16_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Wrench__SWIG_3(resc,resv,argc,argv); + return _wrap_Vector16_end__SWIG_1(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Wrench__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Wrench__SWIG_1(resc,resv,argc,argv); - } + return _wrap_Vector16_end__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Wrench'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Vector16_end'." " Possible C/C++ prototypes are:\n" - " iDynTree::Wrench::Wrench()\n" - " iDynTree::Wrench::Wrench(iDynTree::Force const &,iDynTree::Torque const &)\n" - " iDynTree::Wrench::Wrench(iDynTree::SpatialForceVector const &)\n" - " iDynTree::Wrench::Wrench(iDynTree::Wrench const &)\n"); + " iDynTree::VectorFixSize< 16 >::end() const\n" + " iDynTree::VectorFixSize< 16 >::end()\n"); return 1; } -int _wrap_Wrench_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_Vector16_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + std::size_t result; - if (!SWIG_check_num_args("Wrench_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_plus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Wrench_plus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Wrench_plus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_size" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Wrench const *)arg1)->operator +((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27838,34 +26147,23 @@ int _wrap_Wrench_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Wrench_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_Vector16_data(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + double *result = 0 ; - if (!SWIG_check_num_args("Wrench_minus",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_data",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_minus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Wrench_minus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Wrench_minus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_data" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Wrench const *)arg1)->operator -((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (double *)(arg1)->data(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27873,23 +26171,22 @@ int _wrap_Wrench_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Wrench_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; +int _wrap_Vector16_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Wrench result; - if (!SWIG_check_num_args("Wrench_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_uminus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_zero" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); - result = ((iDynTree::Wrench const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27897,25 +26194,29 @@ int _wrap_Wrench_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Wrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; +int _wrap_Vector16_fillBuffer(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + double *arg2 = (double *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_Wrench",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_fillBuffer",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_fillBuffer" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Vector16_fillBuffer" "', argument " "2"" of type '" "double *""'"); } + arg2 = reinterpret_cast< double * >(argp2); + ((iDynTree::VectorFixSize< 16 > const *)arg1)->fillBuffer(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -27924,16 +26225,23 @@ int _wrap_delete_Wrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_SpatialMomentum__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Vector16_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum *result = 0 ; + std::string result; - if (!SWIG_check_num_args("new_SpatialMomentum",argc,0,0,0)) { + if (!SWIG_check_num_args("Vector16_toString",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_toString" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27941,37 +26249,23 @@ int _wrap_new_SpatialMomentum__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_SpatialMomentum__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinMomentum *arg1 = 0 ; - iDynTree::AngMomentum *arg2 = 0 ; - void *argp1 ; +int _wrap_Vector16_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum *result = 0 ; + std::string result; - if (!SWIG_check_num_args("new_SpatialMomentum",argc,2,2,0)) { + if (!SWIG_check_num_args("Vector16_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::LinMomentum const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::LinMomentum const &""'"); - } - arg1 = reinterpret_cast< iDynTree::LinMomentum * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMomentum" "', argument " "2"" of type '" "iDynTree::AngMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "2"" of type '" "iDynTree::AngMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_display" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::AngMomentum * >(argp2); - result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::LinMomentum const &)*arg1,(iDynTree::AngMomentum const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = ((iDynTree::VectorFixSize< 16 > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -27979,26 +26273,23 @@ int _wrap_new_SpatialMomentum__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_SpatialMomentum__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector16_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum *result = 0 ; + mxArray *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMomentum",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_toMatlab",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_toMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::SpatialForceVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + result = (mxArray *)iDynTree_VectorFixSize_Sl_16_Sg__toMatlab((iDynTree::VectorFixSize< 16 > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28006,26 +26297,24 @@ int _wrap_new_SpatialMomentum__SWIG_2(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_SpatialMomentum__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMomentum *arg1 = 0 ; - void *argp1 ; +int _wrap_Vector16_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum *result = 0 ; - if (!SWIG_check_num_args("new_SpatialMomentum",argc,1,1,0)) { + if (!SWIG_check_num_args("Vector16_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Vector16_fromMatlab" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); - result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::SpatialMomentum const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + arg2 = argv[1]; + iDynTree_VectorFixSize_Sl_16_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28033,140 +26322,26 @@ int _wrap_new_SpatialMomentum__SWIG_3(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_SpatialMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SpatialMomentum__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMomentum__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMomentum__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialMomentum__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMomentum'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialMomentum::SpatialMomentum()\n" - " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::LinMomentum const &,iDynTree::AngMomentum const &)\n" - " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::SpatialForceVector const &)\n" - " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::SpatialMomentum const &)\n"); - return 1; -} - - -int _wrap_SpatialMomentum_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::SpatialMomentum result; - - if (!SWIG_check_num_args("SpatialMomentum_plus",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_plus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMomentum_plus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMomentum_plus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::SpatialMomentum const *)arg1)->operator +((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SpatialMomentum_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_delete_Vector16(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorFixSize< 16 > *arg1 = (iDynTree::VectorFixSize< 16 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("SpatialMomentum_minus",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Vector16",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_minus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMomentum_minus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMomentum_minus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::SpatialMomentum const *)arg1)->operator -((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SpatialMomentum_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialMomentum result; - - if (!SWIG_check_num_args("SpatialMomentum_uminus",argc,1,1,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Vector16" "', argument " "1"" of type '" "iDynTree::VectorFixSize< 16 > *""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_uminus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); + arg1 = reinterpret_cast< iDynTree::VectorFixSize< 16 > * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); - result = ((iDynTree::SpatialMomentum const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28174,26 +26349,16 @@ int _wrap_SpatialMomentum_uminus(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_delete_SpatialMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_Position__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::Position *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialMomentum",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Position",argc,0,0,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::Position *)new iDynTree::Position(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28201,16 +26366,39 @@ int _wrap_delete_SpatialMomentum(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_SpatialAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Position__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_SpatialAcc",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Position",argc,3,3,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Position" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Position" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Position" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (iDynTree::Position *)new iDynTree::Position(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28218,37 +26406,26 @@ int _wrap_new_SpatialAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_SpatialAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinAcceleration *arg1 = 0 ; - iDynTree::AngAcceleration *arg2 = 0 ; +int _wrap_new_Position__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = 0 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_SpatialAcc",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Position",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::LinAcceleration const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Position const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::LinAcceleration const &""'"); - } - arg1 = reinterpret_cast< iDynTree::LinAcceleration * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialAcc" "', argument " "2"" of type '" "iDynTree::AngAcceleration const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "2"" of type '" "iDynTree::AngAcceleration const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::AngAcceleration * >(argp2); - result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::LinAcceleration const &)*arg1,(iDynTree::AngAcceleration const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + result = (iDynTree::Position *)new iDynTree::Position((iDynTree::Position const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28256,26 +26433,31 @@ int _wrap_new_SpatialAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_SpatialAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialMotionVector *arg1 = 0 ; - void *argp1 ; +int _wrap_new_Position__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_SpatialAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Position",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); - result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::SpatialMotionVector const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Position" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (iDynTree::Position *)new iDynTree::Position((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28283,26 +26465,29 @@ int _wrap_new_SpatialAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_SpatialAcc__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialAcc *arg1 = 0 ; +int _wrap_new_Position__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_SpatialAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Position",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Position" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); - result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::SpatialAcc const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); + result = (iDynTree::Position *)new iDynTree::Position(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28310,81 +26495,105 @@ int _wrap_new_SpatialAcc__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_SpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Position(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_SpatialAcc__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Position__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialAcc__SWIG_3(resc,resv,argc,argv); + return _wrap_new_Position__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialAcc__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Position__SWIG_4(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Position__SWIG_3(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_SpatialAcc__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_double(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Position__SWIG_1(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialAcc'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Position'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialAcc::SpatialAcc()\n" - " iDynTree::SpatialAcc::SpatialAcc(iDynTree::LinAcceleration const &,iDynTree::AngAcceleration const &)\n" - " iDynTree::SpatialAcc::SpatialAcc(iDynTree::SpatialMotionVector const &)\n" - " iDynTree::SpatialAcc::SpatialAcc(iDynTree::SpatialAcc const &)\n"); + " iDynTree::Position::Position()\n" + " iDynTree::Position::Position(double,double,double)\n" + " iDynTree::Position::Position(iDynTree::Position const &)\n" + " iDynTree::Position::Position(double const *,unsigned int const)\n" + " iDynTree::Position::Position(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_SpatialAcc_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_Position_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("SpatialAcc_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("Position_changePoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_plus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePoint" "', argument " "1"" of type '" "iDynTree::Position *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialAcc_plus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialAcc_plus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::SpatialAcc const *)arg1)->operator +((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (iDynTree::Position *) &(arg1)->changePoint((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28392,34 +26601,34 @@ int _wrap_SpatialAcc_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_SpatialAcc_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_Position_changeRefPoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("SpatialAcc_minus",argc,2,2,0)) { + if (!SWIG_check_num_args("Position_changeRefPoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_minus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changeRefPoint" "', argument " "1"" of type '" "iDynTree::Position *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialAcc_minus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changeRefPoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialAcc_minus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changeRefPoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::SpatialAcc const *)arg1)->operator -((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (iDynTree::Position *) &(arg1)->changeRefPoint((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28427,23 +26636,34 @@ int _wrap_SpatialAcc_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_SpatialAcc_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; +int _wrap_Position_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("SpatialAcc_uminus",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_changeCoordinateFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_uminus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changeCoordinateFrame" "', argument " "1"" of type '" "iDynTree::Position *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); - result = ((iDynTree::SpatialAcc const *)arg1)->operator -(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (iDynTree::Position *) &(arg1)->changeCoordinateFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28451,26 +26671,37 @@ int _wrap_SpatialAcc_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_SpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; - void *argp1 = 0 ; +int _wrap_Position_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = 0 ; + iDynTree::Position *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Position result; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_compose",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_compose" "', argument " "1"" of type '" "iDynTree::Position const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_compose" "', argument " "1"" of type '" "iDynTree::Position const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_compose" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_compose" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = iDynTree::Position::compose((iDynTree::Position const &)*arg1,(iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28478,16 +26709,26 @@ int _wrap_delete_SpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_ClassicalAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Position_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc *result = 0 ; + iDynTree::Position result; - if (!SWIG_check_num_args("new_ClassicalAcc",argc,0,0,0)) { + if (!SWIG_check_num_args("Position_inverse",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_inverse" "', argument " "1"" of type '" "iDynTree::Position const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_inverse" "', argument " "1"" of type '" "iDynTree::Position const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + result = iDynTree::Position::inverse((iDynTree::Position const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28495,31 +26736,34 @@ int _wrap_new_ClassicalAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_ClassicalAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - unsigned int arg2 ; +int _wrap_Position_changePointOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("new_ClassicalAcc",argc,2,2,0)) { + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_ClassicalAcc" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28527,26 +26771,34 @@ int _wrap_new_ClassicalAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_ClassicalAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ClassicalAcc *arg1 = 0 ; - void *argp1 ; +int _wrap_Position_changePointOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc *result = 0 ; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("new_ClassicalAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const &""'"); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); - result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc((iDynTree::ClassicalAcc const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28554,72 +26806,69 @@ int _wrap_new_ClassicalAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_ClassicalAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_ClassicalAcc__SWIG_0(resc,resv,argc,argv); +int _wrap_Position_changePointOf__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Twist *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + iDynTree::Twist result; + + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ClassicalAcc__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_ClassicalAcc__SWIG_1(resc,resv,argc,argv); - } - } + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ClassicalAcc'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ClassicalAcc::ClassicalAcc()\n" - " iDynTree::ClassicalAcc::ClassicalAcc(double const *,unsigned int const)\n" - " iDynTree::ClassicalAcc::ClassicalAcc(iDynTree::ClassicalAcc const &)\n"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ClassicalAcc_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; - iDynTree::RotationRaw *arg2 = 0 ; +int _wrap_Position_changePointOf__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc *result = 0 ; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("ClassicalAcc_changeCoordFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg2 = reinterpret_cast< iDynTree::RotationRaw * >(argp2); - result = (iDynTree::ClassicalAcc *) &(arg1)->changeCoordFrame((iDynTree::RotationRaw const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28627,16 +26876,34 @@ int _wrap_ClassicalAcc_changeCoordFrame(int resc, mxArray *resv[], int argc, mxA } -int _wrap_ClassicalAcc_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Position_changePointOf__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc result; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("ClassicalAcc_Zero",argc,0,0,0)) { + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::ClassicalAcc::Zero(); - _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28644,44 +26911,34 @@ int _wrap_ClassicalAcc_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_ClassicalAcc_fromSpatial(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - iDynTree::Twist *arg3 = 0 ; +int _wrap_Position_changePointOf__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; + iDynTree::Wrench result; - if (!SWIG_check_num_args("ClassicalAcc_fromSpatial",argc,3,3,0)) { + if (!SWIG_check_num_args("Position_changePointOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_fromSpatial" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_changePointOf" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_fromSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_fromSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ClassicalAcc_fromSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_fromSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_changePointOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } - arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); - (arg1)->fromSpatial((iDynTree::SpatialAcc const &)*arg2,(iDynTree::Twist const &)*arg3); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Position const *)arg1)->changePointOf((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28689,44 +26946,132 @@ int _wrap_ClassicalAcc_fromSpatial(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_ClassicalAcc_toSpatial(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - iDynTree::Twist *arg3 = 0 ; +int _wrap_Position_changePointOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_2(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_4(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_3(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_5(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_changePointOf__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Position_changePointOf'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Position::changePointOf(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::Position::changePointOf(iDynTree::SpatialForceVector const &) const\n" + " iDynTree::Position::changePointOf(iDynTree::Twist const &) const\n" + " iDynTree::Position::changePointOf(iDynTree::SpatialAcc const &) const\n" + " iDynTree::Position::changePointOf(iDynTree::SpatialMomentum const &) const\n" + " iDynTree::Position::changePointOf(iDynTree::Wrench const &) const\n"); + return 1; +} + + +int _wrap_Position_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; + iDynTree::Position result; - if (!SWIG_check_num_args("ClassicalAcc_toSpatial",argc,3,3,0)) { + if (!SWIG_check_num_args("Position_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_toSpatial" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_plus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_toSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_plus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_toSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ClassicalAcc_toSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_toSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_plus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); - ((iDynTree::ClassicalAcc const *)arg1)->toSpatial(*arg2,(iDynTree::Twist const &)*arg3); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator +((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28734,26 +27079,34 @@ int _wrap_ClassicalAcc_toSpatial(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_delete_ClassicalAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; +int _wrap_Position_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Position result; - int is_owned; - if (!SWIG_check_num_args("delete_ClassicalAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_minus",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_minus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_minus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_minus" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator -((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28761,16 +27114,23 @@ int _wrap_delete_ClassicalAcc(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Direction__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Position_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Direction *result = 0 ; + iDynTree::Position result; - if (!SWIG_check_num_args("new_Direction",argc,0,0,0)) { + if (!SWIG_check_num_args("Position_uminus",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Direction *)new iDynTree::Direction(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_uminus" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + result = ((iDynTree::Position const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28778,39 +27138,34 @@ int _wrap_new_Direction__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Direction__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_Position_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Twist *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Direction *result = 0 ; + iDynTree::Twist result; - if (!SWIG_check_num_args("new_Direction",argc,3,3,0)) { + if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Direction" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Direction" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Direction" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (iDynTree::Direction *)new iDynTree::Direction(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28818,26 +27173,34 @@ int _wrap_new_Direction__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Direction__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = 0 ; - void *argp1 ; +int _wrap_Position_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Direction *result = 0 ; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("new_Direction",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Direction" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Direction" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - result = (iDynTree::Direction *)new iDynTree::Direction((iDynTree::Direction const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28845,31 +27208,34 @@ int _wrap_new_Direction__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Direction__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - unsigned int arg2 ; +int _wrap_Position_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Direction *result = 0 ; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("new_Direction",argc,2,2,0)) { + if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Direction" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Direction" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - result = (iDynTree::Direction *)new iDynTree::Direction((double const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28877,91 +27243,34 @@ int _wrap_new_Direction__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Direction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Direction__SWIG_0(resc,resv,argc,argv); +int _wrap_Position_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + iDynTree::SpatialMomentum result; + + if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Direction__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Direction__SWIG_3(resc,resv,argc,argv); - } - } - } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Direction__SWIG_1(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Direction'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Direction::Direction()\n" - " iDynTree::Direction::Direction(double,double,double)\n" - " iDynTree::Direction::Direction(iDynTree::Direction const &)\n" - " iDynTree::Direction::Direction(double const *,unsigned int const)\n"); - return 1; -} - - -int _wrap_Direction_Normalize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; - double arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("Direction_Normalize",argc,2,2,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_Normalize" "', argument " "1"" of type '" "iDynTree::Direction *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Direction_Normalize" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - (arg1)->Normalize(arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28969,22 +27278,34 @@ int _wrap_Direction_Normalize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_Direction_Normalize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; +int _wrap_Position_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Wrench result; - if (!SWIG_check_num_args("Direction_Normalize",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_Normalize" "', argument " "1"" of type '" "iDynTree::Direction *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_mtimes" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - (arg1)->Normalize(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Position_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Position const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -28992,166 +27313,105 @@ int _wrap_Direction_Normalize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_Direction_Normalize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { +int _wrap_Position_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_Direction_Normalize__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_mtimes__SWIG_0(resc,resv,argc,argv); + } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_Direction_Normalize__SWIG_0(resc,resv,argc,argv); + return _wrap_Position_mtimes__SWIG_3(resc,resv,argc,argv); } } } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Direction_Normalize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Direction::Normalize(double)\n" - " iDynTree::Direction::Normalize()\n"); - return 1; -} - - -int _wrap_Direction_isParallel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; - iDynTree::Direction *arg2 = 0 ; - double arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Direction_isParallel",argc,3,3,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_isParallel" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Direction_isParallel" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Direction_isParallel" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Direction_isParallel" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)((iDynTree::Direction const *)arg1)->isParallel((iDynTree::Direction const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Direction_isPerpendicular(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; - iDynTree::Direction *arg2 = 0 ; - double arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - double val3 ; - int ecode3 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Direction_isPerpendicular",argc,3,3,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_isPerpendicular" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_mtimes__SWIG_2(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Direction_isPerpendicular" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_mtimes__SWIG_4(resc,resv,argc,argv); + } + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Direction_isPerpendicular" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Position_mtimes__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Direction_isPerpendicular" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)((iDynTree::Direction const *)arg1)->isPerpendicular((iDynTree::Direction const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Direction_reverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Direction result; - if (!SWIG_check_num_args("Direction_reverse",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_reverse" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - result = ((iDynTree::Direction const *)arg1)->reverse(); - _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Position_mtimes'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Position::operator *(iDynTree::Twist const &) const\n" + " iDynTree::Position::operator *(iDynTree::SpatialForceVector const &) const\n" + " iDynTree::Position::operator *(iDynTree::SpatialAcc const &) const\n" + " iDynTree::Position::operator *(iDynTree::SpatialMomentum const &) const\n" + " iDynTree::Position::operator *(iDynTree::Wrench const &) const\n"); return 1; } -int _wrap_Direction_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; +int _wrap_Position_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Direction_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_toString" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_toString" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - result = ((iDynTree::Direction const *)arg1)->toString(); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + result = ((iDynTree::Position const *)arg1)->toString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -29160,22 +27420,22 @@ int _wrap_Direction_toString(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Direction_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; +int _wrap_Position_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; std::string result; - if (!SWIG_check_num_args("Direction_display",argc,1,1,0)) { + if (!SWIG_check_num_args("Position_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_display" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Position_display" "', argument " "1"" of type '" "iDynTree::Position const *""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - result = ((iDynTree::Direction const *)arg1)->reservedToString(); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); + result = ((iDynTree::Position const *)arg1)->reservedToString(); _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -29184,16 +27444,16 @@ int _wrap_Direction_display(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Direction_Default(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Position_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Direction result; + iDynTree::Position result; - if (!SWIG_check_num_args("Direction_Default",argc,0,0,0)) { + if (!SWIG_check_num_args("Position_Zero",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = iDynTree::Direction::Default(); - _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); + result = iDynTree::Position::Zero(); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29201,22 +27461,22 @@ int _wrap_Direction_Default(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_Direction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; +int _wrap_delete_Position(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Position *arg1 = (iDynTree::Position *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Direction",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Position",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Direction" "', argument " "1"" of type '" "iDynTree::Direction *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Position" "', argument " "1"" of type '" "iDynTree::Position *""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + arg1 = reinterpret_cast< iDynTree::Position * >(argp1); if (is_owned) { delete arg1; } @@ -29228,16 +27488,16 @@ int _wrap_delete_Direction(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Axis__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_GeomVector3__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Axis *result = 0 ; + iDynTree::GeomVector3 *result = 0 ; - if (!SWIG_check_num_args("new_Axis",argc,0,0,0)) { + if (!SWIG_check_num_args("new_GeomVector3",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::Axis *)new iDynTree::Axis(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); + result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29245,37 +27505,71 @@ int _wrap_new_Axis__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Axis__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 ; +int _wrap_new_GeomVector3__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Axis *result = 0 ; + iDynTree::GeomVector3 *result = 0 ; - if (!SWIG_check_num_args("new_Axis",argc,2,2,0)) { + if (!SWIG_check_num_args("new_GeomVector3",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Axis" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "double const *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_GeomVector3" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_GeomVector3__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + mxArray * _out; + iDynTree::GeomVector3 *result = 0 ; + + if (!SWIG_check_num_args("new_GeomVector3",argc,3,3,0)) { + SWIG_fail; } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (iDynTree::Axis *)new iDynTree::Axis((iDynTree::Direction const &)*arg1,(iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_GeomVector3" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_GeomVector3" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29283,26 +27577,29 @@ int _wrap_new_Axis__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Axis__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = 0 ; +int _wrap_new_GeomVector3__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Vector3 arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Axis *result = 0 ; + iDynTree::GeomVector3 *result = 0 ; - if (!SWIG_check_num_args("new_Axis",argc,1,1,0)) { + if (!SWIG_check_num_args("new_GeomVector3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Axis, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Axis const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Axis const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GeomVector3" "', argument " "1"" of type '" "iDynTree::Vector3 const""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_GeomVector3" "', argument " "1"" of type '" "iDynTree::Vector3 const""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Vector3 * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = (iDynTree::Axis *)new iDynTree::Axis((iDynTree::Axis const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); + result = (iDynTree::GeomVector3 *)new iDynTree::GeomVector3(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GeomVector3, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29310,60 +27607,95 @@ int _wrap_new_Axis__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Axis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_GeomVector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Axis__SWIG_0(resc,resv,argc,argv); + return _wrap_new_GeomVector3__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Axis__SWIG_2(resc,resv,argc,argv); + return _wrap_new_GeomVector3__SWIG_3(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_GeomVector3__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_Axis__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_double(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_GeomVector3__SWIG_2(resc,resv,argc,argv); + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Axis'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_GeomVector3'." " Possible C/C++ prototypes are:\n" - " iDynTree::Axis::Axis()\n" - " iDynTree::Axis::Axis(iDynTree::Direction const &,iDynTree::Position const &)\n" - " iDynTree::Axis::Axis(iDynTree::Axis const &)\n"); + " iDynTree::GeomVector3::GeomVector3()\n" + " iDynTree::GeomVector3::GeomVector3(double const *,unsigned int const)\n" + " iDynTree::GeomVector3::GeomVector3(double const,double const,double const)\n" + " iDynTree::GeomVector3::GeomVector3(iDynTree::Vector3 const)\n"); return 1; } -int _wrap_Axis_getDirection(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; +int _wrap_GeomVector3_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Direction *result = 0 ; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getDirection",argc,1,1,0)) { + if (!SWIG_check_num_args("GeomVector3_changeCoordFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getDirection" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = (iDynTree::Direction *) &((iDynTree::Axis const *)arg1)->getDirection(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = ((iDynTree::GeomVector3 const *)arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29371,23 +27703,45 @@ int _wrap_Axis_getDirection(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Axis_getOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; +int _wrap_GeomVector3_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; + iDynTree::GeomVector3 *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getOrigin",argc,1,1,0)) { + if (!SWIG_check_num_args("GeomVector3_compose",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getOrigin" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_compose" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = (iDynTree::Position *) &((iDynTree::Axis const *)arg1)->getOrigin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_compose" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_compose" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "GeomVector3_compose" "', argument " "3"" of type '" "iDynTree::GeomVector3 const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_compose" "', argument " "3"" of type '" "iDynTree::GeomVector3 const &""'"); + } + arg3 = reinterpret_cast< iDynTree::GeomVector3 * >(argp3); + result = ((iDynTree::GeomVector3 const *)arg1)->compose((iDynTree::GeomVector3 const &)*arg2,(iDynTree::GeomVector3 const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29395,33 +27749,34 @@ int _wrap_Axis_getOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Axis_setDirection(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - iDynTree::Direction *arg2 = 0 ; +int _wrap_GeomVector3_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_setDirection",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_inverse",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_setDirection" "', argument " "1"" of type '" "iDynTree::Axis *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_inverse" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_setDirection" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_inverse" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_setDirection" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_inverse" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - (arg1)->setDirection((iDynTree::Direction const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + result = ((iDynTree::GeomVector3 const *)arg1)->inverse((iDynTree::GeomVector3 const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29429,33 +27784,34 @@ int _wrap_Axis_setDirection(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Axis_setOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_GeomVector3_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + double result; - if (!SWIG_check_num_args("Axis_setOrigin",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_dot",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_setOrigin" "', argument " "1"" of type '" "iDynTree::Axis *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_dot" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_setOrigin" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_dot" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_setOrigin" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_dot" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - (arg1)->setOrigin((iDynTree::Position const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + result = (double)((iDynTree::GeomVector3 const *)arg1)->dot((iDynTree::GeomVector3 const &)*arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29463,31 +27819,34 @@ int _wrap_Axis_setOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Axis_getRotationTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_GeomVector3_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getRotationTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTransform" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_plus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTransform" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getRotationTransform(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_plus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_plus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + result = ((iDynTree::GeomVector3 const *)arg1)->operator +((iDynTree::GeomVector3 const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29495,31 +27854,34 @@ int _wrap_Axis_getRotationTransform(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Axis_getRotationTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_GeomVector3_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getRotationTransformDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTransformDerivative" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_minus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTransformDerivative" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getRotationTransformDerivative(arg2); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_minus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_minus" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + result = ((iDynTree::GeomVector3 const *)arg1)->operator -((iDynTree::GeomVector3 const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29527,31 +27889,23 @@ int _wrap_Axis_getRotationTransformDerivative(int resc, mxArray *resv[], int arg } -int _wrap_Axis_getRotationTwist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_GeomVector3_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::Twist result; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getRotationTwist",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_uminus",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTwist" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_uminus" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTwist" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getRotationTwist(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + result = ((iDynTree::GeomVector3 const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29559,31 +27913,23 @@ int _wrap_Axis_getRotationTwist(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Axis_getRotationSpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_GeomVector3_exp(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::Rotation result; - if (!SWIG_check_num_args("Axis_getRotationSpatialAcc",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_exp",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationSpatialAcc" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_exp" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationSpatialAcc" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getRotationSpatialAcc(arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + result = ((iDynTree::GeomVector3 const *)arg1)->exp(); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29591,31 +27937,34 @@ int _wrap_Axis_getRotationSpatialAcc(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_Axis_getTranslationTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_GeomVector3_cross(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; + iDynTree::GeomVector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::GeomVector3 result; - if (!SWIG_check_num_args("Axis_getTranslationTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("GeomVector3_cross",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTransform" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GeomVector3_cross" "', argument " "1"" of type '" "iDynTree::GeomVector3 const *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTransform" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getTranslationTransform(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GeomVector3_cross" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GeomVector3_cross" "', argument " "2"" of type '" "iDynTree::GeomVector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::GeomVector3 * >(argp2); + result = ((iDynTree::GeomVector3 const *)arg1)->cross((iDynTree::GeomVector3 const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::GeomVector3(static_cast< const iDynTree::GeomVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29623,31 +27972,26 @@ int _wrap_Axis_getTranslationTransform(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Axis_getTranslationTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; +int _wrap_delete_GeomVector3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GeomVector3 *arg1 = (iDynTree::GeomVector3 *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Axis_getTranslationTransformDerivative",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_GeomVector3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTransformDerivative" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_GeomVector3" "', argument " "1"" of type '" "iDynTree::GeomVector3 *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTransformDerivative" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getTranslationTransformDerivative(arg2); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::GeomVector3 * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29655,31 +27999,16 @@ int _wrap_Axis_getTranslationTransformDerivative(int resc, mxArray *resv[], int } -int _wrap_Axis_getTranslationTwist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; +int _wrap_new_SpatialMotionVectorBase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Twist result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; - if (!SWIG_check_num_args("Axis_getTranslationTwist",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTwist" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTwist" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getTranslationTwist(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29687,31 +28016,37 @@ int _wrap_Axis_getTranslationTwist(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Axis_getTranslationSpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - double arg2 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMotionVectorBase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *arg1 = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; - if (!SWIG_check_num_args("Axis_getTranslationSpatialAcc",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationSpatialAcc" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationSpatialAcc" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = ((iDynTree::Axis const *)arg1)->getTranslationSpatialAcc(arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMotionVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T * >(argp2); + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &)*arg1,(iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29719,42 +28054,26 @@ int _wrap_Axis_getTranslationSpatialAcc(int resc, mxArray *resv[], int argc, mxA } -int _wrap_Axis_isParallel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - iDynTree::Axis *arg2 = 0 ; - double arg3 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMotionVectorBase__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; - if (!SWIG_check_num_args("Axis_isParallel",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_isParallel" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_isParallel" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_isParallel" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); } - arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Axis_isParallel" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = (bool)((iDynTree::Axis const *)arg1)->isParallel((iDynTree::Axis const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29762,23 +28081,29 @@ int _wrap_Axis_isParallel(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Axis_reverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMotionVectorBase__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Axis result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *result = 0 ; - if (!SWIG_check_num_args("Axis_reverse",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVectorBase",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_reverse" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = ((iDynTree::Axis const *)arg1)->reverse(); - _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *)new iDynTree::SpatialVector< iDynTree::SpatialMotionVector >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29786,23 +28111,70 @@ int _wrap_Axis_reverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Axis_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; +int _wrap_new_SpatialMotionVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SpatialMotionVectorBase__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialMotionVectorBase__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialMotionVectorBase__SWIG_3(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialMotionVectorBase__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMotionVectorBase'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector()\n" + " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &,iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)\n" + " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)\n" + " iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SpatialVector(iDynTree::Span< double const,-1 >)\n"); + return 1; +} + + +int _wrap_SpatialMotionVectorBase_getLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *result = 0 ; - if (!SWIG_check_num_args("Axis_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_getLinearVec3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_toString" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = ((iDynTree::Axis const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *) &(arg1)->getLinearVec3(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29810,23 +28182,23 @@ int _wrap_Axis_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Axis_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; +int _wrap_SpatialMotionVectorBase_getAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *result = 0 ; - if (!SWIG_check_num_args("Axis_display",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_getAngularVec3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_display" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - result = ((iDynTree::Axis const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *) &(arg1)->getAngularVec3(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29834,25 +28206,32 @@ int _wrap_Axis_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Axis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; +int _wrap_SpatialMotionVectorBase_setLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_Axis",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_setLinearVec3",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Axis" "', argument " "1"" of type '" "iDynTree::Axis *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__LinearVector3Type, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &""'"); } + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T * >(argp2); + (arg1)->setLinearVec3((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::LinearVector3T const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -29861,16 +28240,33 @@ int _wrap_delete_Axis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_RotationalInertiaRaw__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SpatialMotionVectorBase_setAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw *result = 0 ; - if (!SWIG_check_num_args("new_RotationalInertiaRaw",argc,0,0,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_setAngularVec3",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::RotationalInertiaRaw *)new iDynTree::RotationalInertiaRaw(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialMotionVector_t__AngularVector3Type, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T * >(argp2); + (arg1)->setAngularVec3((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::AngularVector3T const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29878,39 +28274,31 @@ int _wrap_new_RotationalInertiaRaw__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_RotationalInertiaRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; +int _wrap_SpatialMotionVectorBase_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; unsigned int arg2 ; - unsigned int arg3 ; void *argp1 = 0 ; int res1 = 0 ; unsigned int val2 ; int ecode2 = 0 ; - unsigned int val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw *result = 0 ; + double *result = 0 ; - if (!SWIG_check_num_args("new_RotationalInertiaRaw",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationalInertiaRaw" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_paren" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< double * >(argp1); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_RotationalInertiaRaw" "', argument " "2"" of type '" "unsigned int""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_paren" "', argument " "2"" of type '" "unsigned int""'"); } arg2 = static_cast< unsigned int >(val2); - ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_RotationalInertiaRaw" "', argument " "3"" of type '" "unsigned int""'"); - } - arg3 = static_cast< unsigned int >(val3); - result = (iDynTree::RotationalInertiaRaw *)new iDynTree::RotationalInertiaRaw((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 1 | 0 ); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29918,26 +28306,31 @@ int _wrap_new_RotationalInertiaRaw__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_RotationalInertiaRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationalInertiaRaw *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialMotionVectorBase_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + unsigned int arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw *result = 0 ; + double result; - if (!SWIG_check_num_args("new_RotationalInertiaRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationalInertiaRaw" "', argument " "1"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_RotationalInertiaRaw" "', argument " "1"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_getVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp1); - result = (iDynTree::RotationalInertiaRaw *)new iDynTree::RotationalInertiaRaw((iDynTree::RotationalInertiaRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_getVal" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (double)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -29945,60 +28338,63 @@ int _wrap_new_RotationalInertiaRaw__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_new_RotationalInertiaRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_RotationalInertiaRaw__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_RotationalInertiaRaw__SWIG_2(resc,resv,argc,argv); - } +int _wrap_SpatialMotionVectorBase_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + unsigned int arg2 ; + double arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("SpatialMotionVectorBase_setVal",argc,3,3,0)) { + SWIG_fail; } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_RotationalInertiaRaw__SWIG_1(resc,resv,argc,argv); - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_RotationalInertiaRaw'." - " Possible C/C++ prototypes are:\n" - " iDynTree::RotationalInertiaRaw::RotationalInertiaRaw()\n" - " iDynTree::RotationalInertiaRaw::RotationalInertiaRaw(double const *,unsigned int const,unsigned int const)\n" - " iDynTree::RotationalInertiaRaw::RotationalInertiaRaw(iDynTree::RotationalInertiaRaw const &)\n"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SpatialMotionVectorBase_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_RotationalInertiaRaw_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SpatialMotionVectorBase_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw result; + unsigned int result; - if (!SWIG_check_num_args("RotationalInertiaRaw_Zero",argc,0,0,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_size",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::RotationalInertiaRaw::Zero(); - _out = SWIG_NewPointerObj((new iDynTree::RotationalInertiaRaw(static_cast< const iDynTree::RotationalInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_size" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (unsigned int)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->size(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30006,25 +28402,21 @@ int _wrap_RotationalInertiaRaw_Zero(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_delete_RotationalInertiaRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationalInertiaRaw *arg1 = (iDynTree::RotationalInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_RotationalInertiaRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_zero",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_RotationalInertiaRaw" "', argument " "1"" of type '" "iDynTree::RotationalInertiaRaw *""'"); - } - arg1 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_zero" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -30033,16 +28425,34 @@ int _wrap_delete_RotationalInertiaRaw(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_SpatialInertiaRaw__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SpatialMotionVectorBase_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::Position *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertiaRaw *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("new_SpatialInertiaRaw",argc,0,0,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_changePoint",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SpatialInertiaRaw *)new iDynTree::SpatialInertiaRaw(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (arg1)->changePoint((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30050,45 +28460,34 @@ int _wrap_new_SpatialInertiaRaw__SWIG_0(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_SpatialInertiaRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - iDynTree::PositionRaw *arg2 = 0 ; - iDynTree::RotationalInertiaRaw *arg3 = 0 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_SpatialMotionVectorBase_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::Rotation *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - iDynTree::SpatialInertiaRaw *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("new_SpatialInertiaRaw",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_changeCoordFrame",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SpatialInertiaRaw" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialInertiaRaw" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertiaRaw" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); - } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SpatialInertiaRaw" "', argument " "3"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertiaRaw" "', argument " "3"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); } - arg3 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp3); - result = (iDynTree::SpatialInertiaRaw *)new iDynTree::SpatialInertiaRaw(arg1,(iDynTree::PositionRaw const &)*arg2,(iDynTree::RotationalInertiaRaw const &)*arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30096,26 +28495,37 @@ int _wrap_new_SpatialInertiaRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_SpatialInertiaRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = 0 ; +int _wrap_SpatialMotionVectorBase_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertiaRaw *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("new_SpatialInertiaRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_compose",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialInertiaRaw" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertiaRaw" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = (iDynTree::SpatialInertiaRaw *)new iDynTree::SpatialInertiaRaw((iDynTree::SpatialInertiaRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR compose((iDynTree::SpatialMotionVector const &)*arg1,(iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30123,95 +28533,61 @@ int _wrap_new_SpatialInertiaRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_SpatialInertiaRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SpatialInertiaRaw__SWIG_0(resc,resv,argc,argv); +int _wrap_SpatialMotionVectorBase_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialMotionVector result; + + if (!SWIG_check_num_args("SpatialMotionVectorBase_inverse",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialInertiaRaw__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - if (argc == 3) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialInertiaRaw__SWIG_1(resc,resv,argc,argv); - } - } - } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialInertiaRaw'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialInertiaRaw::SpatialInertiaRaw()\n" - " iDynTree::SpatialInertiaRaw::SpatialInertiaRaw(double const,iDynTree::PositionRaw const &,iDynTree::RotationalInertiaRaw const &)\n" - " iDynTree::SpatialInertiaRaw::SpatialInertiaRaw(iDynTree::SpatialInertiaRaw const &)\n"); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR inverse((iDynTree::SpatialMotionVector const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; - double arg2 ; - iDynTree::PositionRaw *arg3 = 0 ; - iDynTree::RotationalInertiaRaw *arg4 = 0 ; +int _wrap_SpatialMotionVectorBase_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + double result; - if (!SWIG_check_num_args("SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass",argc,4,4,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_dot",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "3"" of type '" "iDynTree::PositionRaw const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "3"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_dot" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg3 = reinterpret_cast< iDynTree::PositionRaw * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "4"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass" "', argument " "4"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &""'"); } - arg4 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp4); - (arg1)->fromRotationalInertiaWrtCenterOfMass(arg2,(iDynTree::PositionRaw const &)*arg3,(iDynTree::RotationalInertiaRaw const &)*arg4); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT * >(argp2); + result = (double)((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->dot((iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT const &)*arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30219,23 +28595,34 @@ int _wrap_SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass(int resc, mxArr } -int _wrap_SpatialInertiaRaw_getMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - double result; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("SpatialInertiaRaw_getMass",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_getMass" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_plus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = (double)((iDynTree::SpatialInertiaRaw const *)arg1)->getMass(); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator +((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30243,23 +28630,34 @@ int _wrap_SpatialInertiaRaw_getMass(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialInertiaRaw_getCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::PositionRaw result; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("SpatialInertiaRaw_getCenterOfMass",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_getCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_minus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = ((iDynTree::SpatialInertiaRaw const *)arg1)->getCenterOfMass(); - _out = SWIG_NewPointerObj((new iDynTree::PositionRaw(static_cast< const iDynTree::PositionRaw& >(result))), SWIGTYPE_p_iDynTree__PositionRaw, SWIG_POINTER_OWN | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator -((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30267,23 +28665,40 @@ int _wrap_SpatialInertiaRaw_getCenterOfMass(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_uminus",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_uminus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SpatialMotionVectorBase_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::SpatialMotionVector result; + + if (!SWIG_check_num_args("SpatialMotionVectorBase_Zero",argc,0,0,0)) { + SWIG_fail; } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = (iDynTree::RotationalInertiaRaw *) &((iDynTree::SpatialInertiaRaw const *)arg1)->getRotationalInertiaWrtFrameOrigin(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 | 0 ); + (void)argv; + result = iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::SWIGTEMPLATEDISAMBIGUATOR Zero(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30291,23 +28706,23 @@ int _wrap_SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin(int resc, mxArray } -int _wrap_SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw result; + iDynTree::Vector6 result; - if (!SWIG_check_num_args("SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_asVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_asVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = ((iDynTree::SpatialInertiaRaw const *)arg1)->getRotationalInertiaWrtCenterOfMass(); - _out = SWIG_NewPointerObj((new iDynTree::RotationalInertiaRaw(static_cast< const iDynTree::RotationalInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->asVector(); + _out = SWIG_NewPointerObj((new iDynTree::Vector6(static_cast< const iDynTree::Vector6& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30315,37 +28730,23 @@ int _wrap_SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass(int resc, mxArra } -int _wrap_SpatialInertiaRaw_combine(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = 0 ; - iDynTree::SpatialInertiaRaw *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialMotionVectorBase_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertiaRaw result; + std::string result; - if (!SWIG_check_num_args("SpatialInertiaRaw_combine",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertiaRaw_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertiaRaw_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertiaRaw_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_toString" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp2); - result = iDynTree::SpatialInertiaRaw::combine((iDynTree::SpatialInertiaRaw const &)*arg1,(iDynTree::SpatialInertiaRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertiaRaw(static_cast< const iDynTree::SpatialInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__SpatialInertiaRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30353,34 +28754,47 @@ int _wrap_SpatialInertiaRaw_combine(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialInertiaRaw_multiply(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_SpatialMotionVectorBase_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + std::string result; - if (!SWIG_check_num_args("SpatialInertiaRaw_multiply",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_multiply" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_display" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertiaRaw_multiply" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SpatialMotionVectorBase_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + mxArray *result = 0 ; + + if (!SWIG_check_num_args("SpatialMotionVectorBase_toMatlab",argc,1,1,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertiaRaw_multiply" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_toMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::SpatialInertiaRaw const *)arg1)->multiply((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (mxArray *)iDynTree_SpatialVector_Sl_iDynTree_SpatialMotionVector_Sg__toMatlab((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const *)arg1); + _out = result; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30388,21 +28802,23 @@ int _wrap_SpatialInertiaRaw_multiply(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SpatialInertiaRaw_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_SpatialMotionVectorBase_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SpatialInertiaRaw_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVectorBase_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertiaRaw_zero" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVectorBase_fromMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - (arg1)->zero(); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + arg2 = argv[1]; + iDynTree_SpatialVector_Sl_iDynTree_SpatialMotionVector_Sg__fromMatlab(arg1,arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -30411,22 +28827,22 @@ int _wrap_SpatialInertiaRaw_zero(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_delete_SpatialInertiaRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = (iDynTree::SpatialInertiaRaw *) 0 ; +int _wrap_delete_SpatialMotionVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_SpatialInertiaRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_SpatialMotionVectorBase",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertiaRaw, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialInertiaRaw" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMotionVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); if (is_owned) { delete arg1; } @@ -30438,16 +28854,16 @@ int _wrap_delete_SpatialInertiaRaw(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_SpatialInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialForceVectorBase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialInertia",argc,0,0,0)) { + if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30455,45 +28871,37 @@ int _wrap_new_SpatialInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_SpatialInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - iDynTree::PositionRaw *arg2 = 0 ; - iDynTree::RotationalInertiaRaw *arg3 = 0 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_new_SpatialForceVectorBase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *arg1 = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *arg2 = 0 ; + void *argp1 ; + int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialInertia",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialInertia" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SpatialInertia" "', argument " "3"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialForceVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "3"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); } - arg3 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp3); - result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia(arg1,(iDynTree::PositionRaw const &)*arg2,(iDynTree::RotationalInertiaRaw const &)*arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T * >(argp2); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &)*arg1,(iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30501,26 +28909,26 @@ int _wrap_new_SpatialInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_SpatialInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertiaRaw *arg1 = 0 ; +int _wrap_new_SpatialForceVectorBase__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertiaRaw * >(argp1); - result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia((iDynTree::SpatialInertiaRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30528,26 +28936,29 @@ int _wrap_new_SpatialInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_SpatialInertia__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = 0 ; +int _wrap_new_SpatialForceVectorBase__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::Span< double const,-1 > > arg1 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *result = 0 ; - if (!SWIG_check_num_args("new_SpatialInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialForceVectorBase",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::Span< double const,-1 >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Span< double const,-1 > * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia((iDynTree::SpatialInertia const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *)new iDynTree::SpatialVector< iDynTree::SpatialForceVector >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30555,90 +28966,70 @@ int _wrap_new_SpatialInertia__SWIG_3(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_SpatialInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialForceVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_SpatialInertia__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SpatialForceVectorBase__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialInertia__SWIG_3(resc,resv,argc,argv); + return _wrap_new_SpatialForceVectorBase__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertiaRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double_const__1_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SpatialInertia__SWIG_2(resc,resv,argc,argv); + return _wrap_new_SpatialForceVectorBase__SWIG_3(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 2) { int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0); + _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SpatialInertia__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_SpatialForceVectorBase__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialInertia'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialForceVectorBase'." " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialInertia::SpatialInertia()\n" - " iDynTree::SpatialInertia::SpatialInertia(double const,iDynTree::PositionRaw const &,iDynTree::RotationalInertiaRaw const &)\n" - " iDynTree::SpatialInertia::SpatialInertia(iDynTree::SpatialInertiaRaw const &)\n" - " iDynTree::SpatialInertia::SpatialInertia(iDynTree::SpatialInertia const &)\n"); + " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector()\n" + " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &,iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)\n" + " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)\n" + " iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SpatialVector(iDynTree::Span< double const,-1 >)\n"); return 1; } -int _wrap_SpatialInertia_combine(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = 0 ; - iDynTree::SpatialInertia *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_getLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia result; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *result = 0 ; - if (!SWIG_check_num_args("SpatialInertia_combine",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_getLinearVec3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); - result = iDynTree::SpatialInertia::combine((iDynTree::SpatialInertia const &)*arg1,(iDynTree::SpatialInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *) &(arg1)->getLinearVec3(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30646,23 +29037,23 @@ int _wrap_SpatialInertia_combine(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_SpatialInertia_asMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; +int _wrap_SpatialForceVectorBase_getAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *result = 0 ; - if (!SWIG_check_num_args("SpatialInertia_asMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_getAngularVec3",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_asMatrix" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = ((iDynTree::SpatialInertia const *)arg1)->asMatrix(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *) &(arg1)->getAngularVec3(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30670,34 +29061,33 @@ int _wrap_SpatialInertia_asMatrix(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SpatialInertia_applyInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_setLinearVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Twist result; - if (!SWIG_check_num_args("SpatialInertia_applyInverse",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_setLinearVec3",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_applyInverse" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_setLinearVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->applyInverse((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T * >(argp2); + (arg1)->setLinearVec3((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30705,23 +29095,33 @@ int _wrap_SpatialInertia_applyInverse(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SpatialInertia_getInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; +int _wrap_SpatialForceVectorBase_setAngularVec3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("SpatialInertia_getInverse",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_setAngularVec3",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getInverse" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = ((iDynTree::SpatialInertia const *)arg1)->getInverse(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_setAngularVec3" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T * >(argp2); + (arg1)->setAngularVec3((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30729,34 +29129,31 @@ int _wrap_SpatialInertia_getInverse(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialInertia_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::SpatialInertia *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + unsigned int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia result; + double *result = 0 ; - if (!SWIG_check_num_args("SpatialInertia_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_plus" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_plus" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_plus" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_paren" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->operator +((iDynTree::SpatialInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_paren" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (double *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30764,34 +29161,31 @@ int _wrap_SpatialInertia_plus(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_SpatialInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + unsigned int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + double result; - if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_getVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_getVal" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (double)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30799,34 +29193,39 @@ int _wrap_SpatialInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + unsigned int arg2 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + bool result; - if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_setVal" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVectorBase_setVal" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SpatialForceVectorBase_setVal" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)(arg1)->setVal(arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30834,34 +29233,23 @@ int _wrap_SpatialInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialInertia_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + unsigned int result; - if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_size" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (unsigned int)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->size(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30869,87 +29257,57 @@ int _wrap_SpatialInertia_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SpatialInertia_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SpatialInertia_mtimes__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SpatialInertia_mtimes__SWIG_2(resc,resv,argc,argv); - } - } +int _wrap_SpatialForceVectorBase_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("SpatialForceVectorBase_zero",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SpatialInertia_mtimes__SWIG_0(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_zero" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SpatialInertia_mtimes'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SpatialInertia::operator *(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::SpatialInertia::operator *(iDynTree::Twist const &) const\n" - " iDynTree::SpatialInertia::operator *(iDynTree::SpatialAcc const &) const\n"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_SpatialInertia_biasWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_changePoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_biasWrench",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_changePoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_biasWrench" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_changePoint" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_biasWrench" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_biasWrench" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_changePoint" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->biasWrench((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (arg1)->changePoint((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30957,34 +29315,34 @@ int _wrap_SpatialInertia_biasWrench(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialInertia_biasWrenchDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_SpatialForceVectorBase_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_biasWrenchDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_changeCoordFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::SpatialInertia const *)arg1)->biasWrenchDerivative((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -30992,74 +29350,37 @@ int _wrap_SpatialInertia_biasWrenchDerivative(int resc, mxArray *resv[], int arg } -int _wrap_SpatialInertia_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SpatialForceVectorBase_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; + void *argp1 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_Zero",argc,0,0,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_compose",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::SpatialInertia::Zero(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SpatialInertia_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Vector10 result; - - if (!SWIG_check_num_args("SpatialInertia_asVector",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_asVector" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = ((iDynTree::SpatialInertia const *)arg1)->asVector(); - _out = SWIG_NewPointerObj((new iDynTree::Vector10(static_cast< const iDynTree::Vector10& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_SpatialInertia_fromVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - iDynTree::Vector10 *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("SpatialInertia_fromVector",argc,2,2,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_fromVector" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_compose" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_fromVector" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_fromVector" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_compose" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector10 * >(argp2); - (arg1)->fromVector((iDynTree::Vector10 const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR compose((iDynTree::SpatialForceVector const &)*arg1,(iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31067,23 +29388,26 @@ int _wrap_SpatialInertia_fromVector(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SpatialInertia_isPhysicallyConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; - void *argp1 = 0 ; +int _wrap_SpatialForceVectorBase_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_isPhysicallyConsistent",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_inverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_isPhysicallyConsistent" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = (bool)((iDynTree::SpatialInertia const *)arg1)->isPhysicallyConsistent(); - _out = SWIG_From_bool(static_cast< bool >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_inverse" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR inverse((iDynTree::SpatialForceVector const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31091,26 +29415,34 @@ int _wrap_SpatialInertia_isPhysicallyConsistent(int resc, mxArray *resv[], int a } -int _wrap_SpatialInertia_momentumRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_dot(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x10 result; + double result; - if (!SWIG_check_num_args("SpatialInertia_momentumRegressor",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_dot",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_dot" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &""'"); } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - result = iDynTree::SpatialInertia::momentumRegressor((iDynTree::Twist const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_dot" "', argument " "2"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT * >(argp2); + result = (double)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->dot((iDynTree::SpatialVector< iDynTree::SpatialForceVector >::DualVectorT const &)*arg2); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31118,37 +29450,34 @@ int _wrap_SpatialInertia_momentumRegressor(int resc, mxArray *resv[], int argc, } -int _wrap_SpatialInertia_momentumDerivativeRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x10 result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_momentumDerivativeRegressor",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_plus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_plus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = iDynTree::SpatialInertia::momentumDerivativeRegressor((iDynTree::Twist const &)*arg1,(iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator +((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31156,48 +29485,34 @@ int _wrap_SpatialInertia_momentumDerivativeRegressor(int resc, mxArray *resv[], } -int _wrap_SpatialInertia_momentumDerivativeSlotineLiRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Twist *arg1 = 0 ; - iDynTree::Twist *arg2 = 0 ; - iDynTree::SpatialAcc *arg3 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - iDynTree::Matrix6x10 result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("SpatialInertia_momentumDerivativeSlotineLiRegressor",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_minus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialForceVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "3"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "3"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialForceVectorBase_minus" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg3 = reinterpret_cast< iDynTree::SpatialAcc * >(argp3); - result = iDynTree::SpatialInertia::momentumDerivativeSlotineLiRegressor((iDynTree::Twist const &)*arg1,(iDynTree::Twist const &)*arg2,(iDynTree::SpatialAcc const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator -((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31205,26 +29520,23 @@ int _wrap_SpatialInertia_momentumDerivativeSlotineLiRegressor(int resc, mxArray } -int _wrap_delete_SpatialInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; +int _wrap_SpatialForceVectorBase_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::SpatialForceVector result; - int is_owned; - if (!SWIG_check_num_args("delete_SpatialInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_uminus",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_uminus" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31232,16 +29544,16 @@ int _wrap_delete_SpatialInertia(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_ArticulatedBodyInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SpatialForceVectorBase_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,0,0,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_Zero",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); + result = iDynTree::SpatialVector< iDynTree::SpatialForceVector >::SWIGTEMPLATEDISAMBIGUATOR Zero(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31249,39 +29561,23 @@ int _wrap_new_ArticulatedBodyInertia__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_new_ArticulatedBodyInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - unsigned int arg2 ; - unsigned int arg3 ; +int _wrap_SpatialForceVectorBase_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; - unsigned int val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + iDynTree::Vector6 result; - if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_asVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_asVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_ArticulatedBodyInertia" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_ArticulatedBodyInertia" "', argument " "3"" of type '" "unsigned int""'"); - } - arg3 = static_cast< unsigned int >(val3); - result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->asVector(); + _out = SWIG_NewPointerObj((new iDynTree::Vector6(static_cast< const iDynTree::Vector6& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31289,26 +29585,23 @@ int _wrap_new_ArticulatedBodyInertia__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_new_ArticulatedBodyInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialInertia *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + std::string result; - if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_toString" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); - result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((iDynTree::SpatialInertia const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31316,26 +29609,23 @@ int _wrap_new_ArticulatedBodyInertia__SWIG_2(int resc, mxArray *resv[], int argc } -int _wrap_new_ArticulatedBodyInertia__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialForceVectorBase_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + std::string result; - if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_display" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((iDynTree::ArticulatedBodyInertia const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = ((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31343,77 +29633,48 @@ int _wrap_new_ArticulatedBodyInertia__SWIG_3(int resc, mxArray *resv[], int argc } -int _wrap_new_ArticulatedBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_ArticulatedBodyInertia__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ArticulatedBodyInertia__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ArticulatedBodyInertia__SWIG_3(resc,resv,argc,argv); - } +int _wrap_SpatialForceVectorBase_toMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + mxArray *result = 0 ; + + if (!SWIG_check_num_args("SpatialForceVectorBase_toMatlab",argc,1,1,0)) { + SWIG_fail; } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_ArticulatedBodyInertia__SWIG_1(resc,resv,argc,argv); - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_toMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ArticulatedBodyInertia'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia()\n" - " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(double const *,unsigned int const,unsigned int const)\n" - " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(iDynTree::SpatialInertia const &)\n" - " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(iDynTree::ArticulatedBodyInertia const &)\n"); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (mxArray *)iDynTree_SpatialVector_Sl_iDynTree_SpatialForceVector_Sg__toMatlab((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const *)arg1); + _out = result; + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_SpatialForceVectorBase_fromMatlab(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; + mxArray *arg2 = (mxArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearLinearSubmatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialForceVectorBase_fromMatlab",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearLinearSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVectorBase_fromMatlab" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &(arg1)->getLinearLinearSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + arg2 = argv[1]; + iDynTree_SpatialVector_Sl_iDynTree_SpatialForceVector_Sg__fromMatlab(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31421,23 +29682,26 @@ int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_0(int resc, mxAr } -int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_delete_SpatialForceVectorBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = (iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearAngularSubmatrix",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SpatialForceVectorBase",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialForceVectorBase" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &(arg1)->getLinearAngularSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31445,23 +29709,16 @@ int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_0(int resc, mxA } -int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; + iDynTree::Dummy *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getAngularAngularSubmatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Dummy",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getAngularAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &(arg1)->getAngularAngularSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + (void)argv; + result = (iDynTree::Dummy *)new iDynTree::Dummy(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Dummy, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31469,23 +29726,26 @@ int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_0(int resc, mx } -int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_delete_Dummy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Dummy *arg1 = (iDynTree::Dummy *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearLinearSubmatrix",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Dummy",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Dummy, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearLinearSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Dummy" "', argument " "1"" of type '" "iDynTree::Dummy *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getLinearLinearSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Dummy * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31493,51 +29753,54 @@ int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_1(int resc, mxAr } -int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_0(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_new_SpatialMotionVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::SpatialMotionVector *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getLinearLinearSubmatrix'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyInertia::getLinearLinearSubmatrix()\n" - " iDynTree::ArticulatedBodyInertia::getLinearLinearSubmatrix() const\n"); + if (!SWIG_check_num_args("new_SpatialMotionVector",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMotionVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinearMotionVector3 *arg1 = 0 ; + iDynTree::AngularMotionVector3 *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; + iDynTree::SpatialMotionVector *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearAngularSubmatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVector",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::LinearMotionVector3 const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getLinearAngularSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::LinearMotionVector3 const &""'"); + } + arg1 = reinterpret_cast< iDynTree::LinearMotionVector3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMotionVector" "', argument " "2"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "2"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp2); + result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::LinearMotionVector3 const &)*arg1,(iDynTree::AngularMotionVector3 const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31545,51 +29808,53 @@ int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_1(int resc, mxA } -int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_0(resc,resv,argc,argv); - } +int _wrap_new_SpatialMotionVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialMotionVector *result = 0 ; + + if (!SWIG_check_num_args("new_SpatialMotionVector",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_1(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getLinearAngularSubmatrix'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyInertia::getLinearAngularSubmatrix()\n" - " iDynTree::ArticulatedBodyInertia::getLinearAngularSubmatrix() const\n"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::SpatialMotionVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMotionVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialMotionVector > *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; + iDynTree::SpatialMotionVector *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getAngularAngularSubmatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialMotionVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getAngularAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getAngularAngularSubmatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialMotionVector > * >(argp1); + result = (iDynTree::SpatialMotionVector *)new iDynTree::SpatialMotionVector((iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31597,65 +29862,113 @@ int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_1(int resc, mx } -int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialMotionVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SpatialMotionVector__SWIG_0(resc,resv,argc,argv); + } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SpatialMotionVector__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialMotionVector_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_1(resc,resv,argc,argv); + return _wrap_new_SpatialMotionVector__SWIG_3(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialMotionVector__SWIG_1(resc,resv,argc,argv); + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getAngularAngularSubmatrix'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMotionVector'." " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyInertia::getAngularAngularSubmatrix()\n" - " iDynTree::ArticulatedBodyInertia::getAngularAngularSubmatrix() const\n"); + " iDynTree::SpatialMotionVector::SpatialMotionVector()\n" + " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::LinearMotionVector3 const &,iDynTree::AngularMotionVector3 const &)\n" + " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::SpatialMotionVector const &)\n" + " iDynTree::SpatialMotionVector::SpatialMotionVector(iDynTree::SpatialVector< iDynTree::SpatialMotionVector > const &)\n"); return 1; } -int _wrap_ArticulatedBodyInertia_combine(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = 0 ; - iDynTree::ArticulatedBodyInertia *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialMotionVector_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; + double arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::SpatialMotionVector result; + + if (!SWIG_check_num_args("SpatialMotionVector_mtimes",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialMotionVector_mtimes" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::SpatialMotionVector const *)arg1)->operator *(arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SpatialMotionVector_cross__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_combine",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMotionVector_cross",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_combine" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_combine" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_cross" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_combine" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_combine" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); - result = iDynTree::ArticulatedBodyInertia::combine((iDynTree::ArticulatedBodyInertia const &)*arg1,(iDynTree::ArticulatedBodyInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::SpatialMotionVector const *)arg1)->cross((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31663,34 +29976,34 @@ int _wrap_ArticulatedBodyInertia_combine(int resc, mxArray *resv[], int argc, mx } -int _wrap_ArticulatedBodyInertia_applyInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_SpatialMotionVector_cross__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_applyInverse",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMotionVector_cross",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_cross" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMotionVector_cross" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->applyInverse((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::SpatialMotionVector const *)arg1)->cross((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31698,22 +30011,60 @@ int _wrap_ArticulatedBodyInertia_applyInverse(int resc, mxArray *resv[], int arg } -int _wrap_ArticulatedBodyInertia_asMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_SpatialMotionVector_cross(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SpatialMotionVector_cross__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SpatialMotionVector_cross__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SpatialMotionVector_cross'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SpatialMotionVector::cross(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::SpatialMotionVector::cross(iDynTree::SpatialForceVector const &) const\n"); + return 1; +} + + +int _wrap_SpatialMotionVector_asCrossProductMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_asMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVector_asCrossProductMatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_asMatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_asCrossProductMatrix" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->asMatrix(); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = ((iDynTree::SpatialMotionVector const *)arg1)->asCrossProductMatrix(); _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -31722,22 +30073,22 @@ int _wrap_ArticulatedBodyInertia_asMatrix(int resc, mxArray *resv[], int argc, m } -int _wrap_ArticulatedBodyInertia_getInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_SpatialMotionVector_asCrossProductMatrixWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_getInverse",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialMotionVector_asCrossProductMatrixWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getInverse" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_asCrossProductMatrixWrench" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->getInverse(); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = ((iDynTree::SpatialMotionVector const *)arg1)->asCrossProductMatrixWrench(); _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -31746,34 +30097,23 @@ int _wrap_ArticulatedBodyInertia_getInverse(int resc, mxArray *resv[], int argc, } -int _wrap_ArticulatedBodyInertia_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - iDynTree::ArticulatedBodyInertia *arg2 = 0 ; +int _wrap_SpatialMotionVector_exp(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::Transform result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_plus",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMotionVector_exp",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_plus" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_plus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_plus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMotionVector_exp" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const *""'"); } - arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator +((iDynTree::ArticulatedBodyInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = ((iDynTree::SpatialMotionVector const *)arg1)->exp(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31781,34 +30121,43 @@ int _wrap_ArticulatedBodyInertia_plus(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_ArticulatedBodyInertia_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - iDynTree::ArticulatedBodyInertia *arg2 = 0 ; +int _wrap_delete_SpatialMotionVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = (iDynTree::SpatialMotionVector *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_minus",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SpatialMotionVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_minus" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMotionVector" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_minus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + if (is_owned) { + delete arg1; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_minus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_SpatialForceVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::SpatialForceVector *result = 0 ; + + if (!SWIG_check_num_args("new_SpatialForceVector",argc,0,0,0)) { + SWIG_fail; } - arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator -((iDynTree::ArticulatedBodyInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31816,34 +30165,37 @@ int _wrap_ArticulatedBodyInertia_minus(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_ArticulatedBodyInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialForceVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector::LinearVector3T *arg1 = 0 ; + iDynTree::SpatialForceVector::AngularVector3T *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::SpatialForceVector *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialForceVector",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector::LinearVector3T const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector::LinearVector3T const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector::LinearVector3T * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialForceVector" "', argument " "2"" of type '" "iDynTree::SpatialForceVector::AngularVector3T const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "2"" of type '" "iDynTree::SpatialForceVector::AngularVector3T const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialForceVector::AngularVector3T * >(argp2); + result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialForceVector::LinearVector3T const &)*arg1,(iDynTree::SpatialForceVector::AngularVector3T const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31851,34 +30203,53 @@ int _wrap_ArticulatedBodyInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int a } -int _wrap_ArticulatedBodyInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialForceVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + iDynTree::SpatialForceVector *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialForceVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialForceVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_SpatialForceVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialVector< iDynTree::SpatialForceVector > *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialForceVector *result = 0 ; + + if (!SWIG_check_num_args("new_SpatialForceVector",argc,1,1,0)) { + SWIG_fail; } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialVector< iDynTree::SpatialForceVector > * >(argp1); + result = (iDynTree::SpatialForceVector *)new iDynTree::SpatialForceVector((iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31886,59 +30257,72 @@ int _wrap_ArticulatedBodyInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int a } -int _wrap_ArticulatedBodyInertia_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_SpatialForceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SpatialForceVector__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ArticulatedBodyInertia_mtimes__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_SpatialForceVector__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialForceVector__SWIG_3(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0); _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ArticulatedBodyInertia_mtimes__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SpatialForceVector__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_mtimes'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialForceVector'." " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyInertia::operator *(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::ArticulatedBodyInertia::operator *(iDynTree::SpatialAcc const &) const\n"); + " iDynTree::SpatialForceVector::SpatialForceVector()\n" + " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialForceVector::LinearVector3T const &,iDynTree::SpatialForceVector::AngularVector3T const &)\n" + " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialForceVector const &)\n" + " iDynTree::SpatialForceVector::SpatialForceVector(iDynTree::SpatialVector< iDynTree::SpatialForceVector > const &)\n"); return 1; } -int _wrap_ArticulatedBodyInertia_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; +int _wrap_delete_SpatialForceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = (iDynTree::SpatialForceVector *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("ArticulatedBodyInertia_zero",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SpatialForceVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_zero" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialForceVector" "', argument " "1"" of type '" "iDynTree::SpatialForceVector *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -31947,34 +30331,31 @@ int _wrap_ArticulatedBodyInertia_zero(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_ArticulatedBodyInertia_ABADyadHelper(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; +int _wrap_SpatialForceVector_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = (iDynTree::SpatialForceVector *) 0 ; double arg2 ; - void *argp1 ; + void *argp1 = 0 ; int res1 = 0 ; double val2 ; int ecode2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("ArticulatedBodyInertia_ABADyadHelper",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialForceVector_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialForceVector_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const *""'"); } arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "2"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialForceVector_mtimes" "', argument " "2"" of type '" "double""'"); } arg2 = static_cast< double >(val2); - result = iDynTree::ArticulatedBodyInertia::ABADyadHelper((iDynTree::SpatialForceVector const &)*arg1,arg2); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + result = ((iDynTree::SpatialForceVector const *)arg1)->operator *(arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -31982,53 +30363,16 @@ int _wrap_ArticulatedBodyInertia_ABADyadHelper(int resc, mxArray *resv[], int ar } -int _wrap_ArticulatedBodyInertia_ABADyadHelperLin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SpatialForceVector *arg1 = 0 ; - double arg2 ; - iDynTree::SpatialForceVector *arg3 = 0 ; - double arg4 ; - void *argp1 ; - int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; - double val4 ; - int ecode4 = 0 ; +int _wrap_new_Twist__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyInertia_ABADyadHelperLin",argc,4,4,0)) { + if (!SWIG_check_num_args("new_Twist",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "3"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "3"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - arg3 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = iDynTree::ArticulatedBodyInertia::ABADyadHelperLin((iDynTree::SpatialForceVector const &)*arg1,arg2,(iDynTree::SpatialForceVector const &)*arg3,arg4); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::Twist *)new iDynTree::Twist(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32036,26 +30380,37 @@ int _wrap_ArticulatedBodyInertia_ABADyadHelperLin(int resc, mxArray *resv[], int } -int _wrap_delete_ArticulatedBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; - void *argp1 = 0 ; +int _wrap_new_Twist__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinVelocity *arg1 = 0 ; + iDynTree::AngVelocity *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Twist *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_ArticulatedBodyInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Twist",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::LinVelocity const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::LinVelocity const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::LinVelocity * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Twist" "', argument " "2"" of type '" "iDynTree::AngVelocity const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "2"" of type '" "iDynTree::AngVelocity const &""'"); + } + arg2 = reinterpret_cast< iDynTree::AngVelocity * >(argp2); + result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::LinVelocity const &)*arg1,(iDynTree::AngVelocity const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32063,30 +30418,26 @@ int _wrap_delete_ArticulatedBodyInertia(int resc, mxArray *resv[], int argc, mxA } -int _wrap_RigidBodyInertiaNonLinearParametrization_mass_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - double arg2 ; - void *argp1 = 0 ; +int _wrap_new_Twist__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; + iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_mass_set",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Twist",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->mass = arg2; - _out = (mxArray*)0; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::SpatialMotionVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32094,23 +30445,26 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_mass_set(int resc, mxArray *r } -int _wrap_RigidBodyInertiaNonLinearParametrization_mass_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - void *argp1 = 0 ; +int _wrap_new_Twist__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - double result; + iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_mass_get",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Twist",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = (double) ((arg1)->mass); - _out = SWIG_From_double(static_cast< double >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Twist" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + result = (iDynTree::Twist *)new iDynTree::Twist((iDynTree::Twist const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32118,54 +30472,81 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_mass_get(int resc, mxArray *r } -int _wrap_RigidBodyInertiaNonLinearParametrization_com_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::Position *arg2 = (iDynTree::Position *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_com_set",argc,2,2,0)) { - SWIG_fail; +int _wrap_new_Twist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Twist__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_com_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Twist__SWIG_3(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_com_set" "', argument " "2"" of type '" "iDynTree::Position *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Twist__SWIG_2(resc,resv,argc,argv); + } } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - if (arg1) (arg1)->com = *arg2; - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Twist__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Twist'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Twist::Twist()\n" + " iDynTree::Twist::Twist(iDynTree::LinVelocity const &,iDynTree::AngVelocity const &)\n" + " iDynTree::Twist::Twist(iDynTree::SpatialMotionVector const &)\n" + " iDynTree::Twist::Twist(iDynTree::Twist const &)\n"); return 1; } -int _wrap_RigidBodyInertiaNonLinearParametrization_com_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_Twist_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::Twist result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_com_get",argc,1,1,0)) { + if (!SWIG_check_num_args("Twist_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_com_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_plus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = (iDynTree::Position *)& ((arg1)->com); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_plus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_plus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Twist const *)arg1)->operator +((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32173,30 +30554,34 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_com_get(int resc, mxArray *re } -int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::Rotation *arg2 = (iDynTree::Rotation *) 0 ; +int _wrap_Twist_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Twist result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set",argc,2,2,0)) { + if (!SWIG_check_num_args("Twist_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_minus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set" "', argument " "2"" of type '" "iDynTree::Rotation *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_minus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - if (arg1) (arg1)->link_R_centroidal = *arg2; - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_minus" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Twist const *)arg1)->operator -((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32204,23 +30589,23 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set(int res } -int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_Twist_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Twist result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get",argc,1,1,0)) { + if (!SWIG_check_num_args("Twist_uminus",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_uminus" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = (iDynTree::Rotation *)& ((arg1)->link_R_centroidal); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + result = ((iDynTree::Twist const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32228,30 +30613,34 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get(int res } -int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::Vector3 *arg2 = (iDynTree::Vector3 *) 0 ; +int _wrap_Twist_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set",argc,2,2,0)) { + if (!SWIG_check_num_args("Twist_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_mtimes" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set" "', argument " "2"" of type '" "iDynTree::Vector3 *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); - if (arg1) (arg1)->centralSecondMomentOfMass = *arg2; - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Twist const *)arg1)->operator *((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32259,23 +30648,34 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set } -int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_Twist_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Vector3 *result = 0 ; + iDynTree::Wrench result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get",argc,1,1,0)) { + if (!SWIG_check_num_args("Twist_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Twist_mtimes" "', argument " "1"" of type '" "iDynTree::Twist const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = (iDynTree::Vector3 *)& ((arg1)->centralSecondMomentOfMass); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Twist_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Twist const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32283,23 +30683,64 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get } -int _wrap_RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_Twist_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Twist_mtimes__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Twist_mtimes__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Twist_mtimes'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Twist::operator *(iDynTree::Twist const &) const\n" + " iDynTree::Twist::operator *(iDynTree::SpatialMomentum const &) const\n"); + return 1; +} + + +int _wrap_delete_Twist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = (iDynTree::Twist *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Twist",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Twist" "', argument " "1"" of type '" "iDynTree::Twist *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->getLinkCentroidalTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32307,33 +30748,16 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform(in } -int _wrap_RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::SpatialInertia *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_Wrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Wrench",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); - } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); - (arg1)->fromRigidBodyInertia((iDynTree::SpatialInertia const &)*arg2); - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::Wrench *)new iDynTree::Wrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32341,33 +30765,37 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia(int resc } -int _wrap_RigidBodyInertiaNonLinearParametrization_fromInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::Vector10 *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_Wrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Force *arg1 = 0 ; + iDynTree::Torque *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromInertialParameters",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Wrench",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Force const &""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Force const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Force * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Wrench" "', argument " "2"" of type '" "iDynTree::Torque const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "2"" of type '" "iDynTree::Torque const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector10 * >(argp2); - (arg1)->fromInertialParameters((iDynTree::Vector10 const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Torque * >(argp2); + result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::Force const &)*arg1,(iDynTree::Torque const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32375,23 +30803,26 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_fromInertialParameters(int re } -int _wrap_RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - void *argp1 = 0 ; +int _wrap_new_Wrench__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SpatialInertia result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Wrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->toRigidBodyInertia(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::SpatialForceVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32399,23 +30830,26 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia(int resc, } -int _wrap_RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - void *argp1 = 0 ; +int _wrap_new_Wrench__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Wrench *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Wrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Wrench, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench const &""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = (bool)((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->isPhysicallyConsistent(); - _out = SWIG_From_bool(static_cast< bool >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); + result = (iDynTree::Wrench *)new iDynTree::Wrench((iDynTree::Wrench const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32423,57 +30857,81 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent(int re } -int _wrap_RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Vector16 result; - - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); +int _wrap_new_Wrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Wrench__SWIG_0(resc,resv,argc,argv); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->asVectorWithRotationAsVec(); - _out = SWIG_NewPointerObj((new iDynTree::Vector16(static_cast< const iDynTree::Vector16& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Wrench__SWIG_3(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Wrench__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Wrench__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Wrench'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Wrench::Wrench()\n" + " iDynTree::Wrench::Wrench(iDynTree::Force const &,iDynTree::Torque const &)\n" + " iDynTree::Wrench::Wrench(iDynTree::SpatialForceVector const &)\n" + " iDynTree::Wrench::Wrench(iDynTree::Wrench const &)\n"); return 1; } -int _wrap_RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; - iDynTree::Vector16 *arg2 = 0 ; +int _wrap_Wrench_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Wrench result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec",argc,2,2,0)) { + if (!SWIG_check_num_args("Wrench_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_plus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 ); + arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "2"" of type '" "iDynTree::Vector16 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Wrench_plus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "2"" of type '" "iDynTree::Vector16 const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Wrench_plus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector16 * >(argp2); - (arg1)->fromVectorWithRotationAsVec((iDynTree::Vector16 const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Wrench const *)arg1)->operator +((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32481,23 +30939,34 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec(i } -int _wrap_RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_Wrench_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix10x16 result; + iDynTree::Wrench result; - if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec",argc,1,1,0)) { + if (!SWIG_check_num_args("Wrench_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_minus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); - result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->getGradientWithRotationAsVec(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix10x16(static_cast< const iDynTree::Matrix10x16& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Wrench_minus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Wrench_minus" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Wrench const *)arg1)->operator -((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32505,16 +30974,23 @@ int _wrap_RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec( } -int _wrap_new_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Wrench_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::RigidBodyInertiaNonLinearParametrization *result = 0 ; + iDynTree::Wrench result; - if (!SWIG_check_num_args("new_RigidBodyInertiaNonLinearParametrization",argc,0,0,0)) { + if (!SWIG_check_num_args("Wrench_uminus",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::RigidBodyInertiaNonLinearParametrization *)new iDynTree::RigidBodyInertiaNonLinearParametrization(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Wrench_uminus" "', argument " "1"" of type '" "iDynTree::Wrench const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); + result = ((iDynTree::Wrench const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32522,22 +30998,22 @@ int _wrap_new_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *resv[] } -int _wrap_delete_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; +int _wrap_delete_Wrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Wrench *arg1 = (iDynTree::Wrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_RigidBodyInertiaNonLinearParametrization",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Wrench",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_RigidBodyInertiaNonLinearParametrization" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Wrench" "', argument " "1"" of type '" "iDynTree::Wrench *""'"); } - arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + arg1 = reinterpret_cast< iDynTree::Wrench * >(argp1); if (is_owned) { delete arg1; } @@ -32549,104 +31025,16 @@ int _wrap_delete_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *res } -int _wrap_new_RotationRaw__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialMomentum__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum *result = 0 ; - if (!SWIG_check_num_args("new_RotationRaw",argc,0,0,0)) { + if (!SWIG_check_num_args("new_SpatialMomentum",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::RotationRaw *)new iDynTree::RotationRaw(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_RotationRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double arg4 ; - double arg5 ; - double arg6 ; - double arg7 ; - double arg8 ; - double arg9 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - double val5 ; - int ecode5 = 0 ; - double val6 ; - int ecode6 = 0 ; - double val7 ; - int ecode7 = 0 ; - double val8 ; - int ecode8 = 0 ; - double val9 ; - int ecode9 = 0 ; - mxArray * _out; - iDynTree::RotationRaw *result = 0 ; - - if (!SWIG_check_num_args("new_RotationRaw",argc,9,9,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_RotationRaw" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_RotationRaw" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_RotationRaw" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "new_RotationRaw" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - ecode5 = SWIG_AsVal_double(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "new_RotationRaw" "', argument " "5"" of type '" "double""'"); - } - arg5 = static_cast< double >(val5); - ecode6 = SWIG_AsVal_double(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "new_RotationRaw" "', argument " "6"" of type '" "double""'"); - } - arg6 = static_cast< double >(val6); - ecode7 = SWIG_AsVal_double(argv[6], &val7); - if (!SWIG_IsOK(ecode7)) { - SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "new_RotationRaw" "', argument " "7"" of type '" "double""'"); - } - arg7 = static_cast< double >(val7); - ecode8 = SWIG_AsVal_double(argv[7], &val8); - if (!SWIG_IsOK(ecode8)) { - SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "new_RotationRaw" "', argument " "8"" of type '" "double""'"); - } - arg8 = static_cast< double >(val8); - ecode9 = SWIG_AsVal_double(argv[8], &val9); - if (!SWIG_IsOK(ecode9)) { - SWIG_exception_fail(SWIG_ArgError(ecode9), "in method '" "new_RotationRaw" "', argument " "9"" of type '" "double""'"); - } - arg9 = static_cast< double >(val9); - result = (iDynTree::RotationRaw *)new iDynTree::RotationRaw(arg1,arg2,arg3,arg4,arg5,arg6,arg7,arg8,arg9); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 1 | 0 ); + result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32654,39 +31042,37 @@ int _wrap_new_RotationRaw__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_RotationRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double *arg1 = (double *) 0 ; - unsigned int arg2 ; - unsigned int arg3 ; - void *argp1 = 0 ; +int _wrap_new_SpatialMomentum__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinMomentum *arg1 = 0 ; + iDynTree::AngMomentum *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; - unsigned int val2 ; - int ecode2 = 0 ; - unsigned int val3 ; - int ecode3 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum *result = 0 ; - if (!SWIG_check_num_args("new_RotationRaw",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SpatialMomentum",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationRaw" "', argument " "1"" of type '" "double const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::LinMomentum const &""'"); } - arg1 = reinterpret_cast< double * >(argp1); - ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_RotationRaw" "', argument " "2"" of type '" "unsigned int""'"); - } - arg2 = static_cast< unsigned int >(val2); - ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_RotationRaw" "', argument " "3"" of type '" "unsigned int""'"); - } - arg3 = static_cast< unsigned int >(val3); - result = (iDynTree::RotationRaw *)new iDynTree::RotationRaw((double const *)arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 1 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::LinMomentum const &""'"); + } + arg1 = reinterpret_cast< iDynTree::LinMomentum * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialMomentum" "', argument " "2"" of type '" "iDynTree::AngMomentum const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "2"" of type '" "iDynTree::AngMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::AngMomentum * >(argp2); + result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::LinMomentum const &)*arg1,(iDynTree::AngMomentum const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32694,29 +31080,26 @@ int _wrap_new_RotationRaw__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_RotationRaw__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; +int _wrap_new_SpatialMomentum__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum *result = 0 ; - if (!SWIG_check_num_args("new_RotationRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialMomentum",argc,1,1,0)) { SWIG_fail; } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationRaw" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_RotationRaw" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - result = (iDynTree::RotationRaw *)new iDynTree::RotationRaw(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::SpatialForceVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32724,26 +31107,26 @@ int _wrap_new_RotationRaw__SWIG_3(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_RotationRaw__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = 0 ; +int _wrap_new_SpatialMomentum__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMomentum *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum *result = 0 ; - if (!SWIG_check_num_args("new_RotationRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialMomentum",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationRaw" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_RotationRaw" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - result = (iDynTree::RotationRaw *)new iDynTree::RotationRaw((iDynTree::RotationRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); + result = (iDynTree::SpatialMomentum *)new iDynTree::SpatialMomentum((iDynTree::SpatialMomentum const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMomentum, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32751,147 +31134,81 @@ int _wrap_new_RotationRaw__SWIG_4(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_RotationRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_RotationRaw__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SpatialMomentum__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_RotationRaw__SWIG_3(resc,resv,argc,argv); + return _wrap_new_SpatialMomentum__SWIG_3(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_RotationRaw__SWIG_4(resc,resv,argc,argv); + return _wrap_new_SpatialMomentum__SWIG_2(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_RotationRaw__SWIG_2(resc,resv,argc,argv); - } - } - } - } - if (argc == 9) { - int _v; - { - int res = SWIG_AsVal_double(argv[0], NULL); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[1], NULL); - _v = SWIG_CheckState(res); - } if (_v) { - { - int res = SWIG_AsVal_double(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[3], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[4], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[5], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[6], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[7], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[8], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_RotationRaw__SWIG_1(resc,resv,argc,argv); - } - } - } - } - } - } - } + return _wrap_new_SpatialMomentum__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_RotationRaw'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialMomentum'." " Possible C/C++ prototypes are:\n" - " iDynTree::RotationRaw::RotationRaw()\n" - " iDynTree::RotationRaw::RotationRaw(double,double,double,double,double,double,double,double,double)\n" - " iDynTree::RotationRaw::RotationRaw(double const *,unsigned int const,unsigned int const)\n" - " iDynTree::RotationRaw::RotationRaw(iDynTree::MatrixView< double const >)\n" - " iDynTree::RotationRaw::RotationRaw(iDynTree::RotationRaw const &)\n"); + " iDynTree::SpatialMomentum::SpatialMomentum()\n" + " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::LinMomentum const &,iDynTree::AngMomentum const &)\n" + " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::SpatialForceVector const &)\n" + " iDynTree::SpatialMomentum::SpatialMomentum(iDynTree::SpatialMomentum const &)\n"); return 1; } -int _wrap_RotationRaw_changeOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; - iDynTree::RotationRaw *arg2 = 0 ; +int _wrap_SpatialMomentum_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("RotationRaw_changeOrientFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMomentum_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_changeOrientFrame" "', argument " "1"" of type '" "iDynTree::RotationRaw *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_plus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMomentum_plus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMomentum_plus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg2 = reinterpret_cast< iDynTree::RotationRaw * >(argp2); - result = (iDynTree::RotationRaw *) &(arg1)->changeOrientFrame((iDynTree::RotationRaw const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::SpatialMomentum const *)arg1)->operator +((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32899,34 +31216,34 @@ int _wrap_RotationRaw_changeOrientFrame(int resc, mxArray *resv[], int argc, mxA } -int _wrap_RotationRaw_changeRefOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; - iDynTree::RotationRaw *arg2 = 0 ; +int _wrap_SpatialMomentum_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw *result = 0 ; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("RotationRaw_changeRefOrientFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMomentum_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_changeRefOrientFrame" "', argument " "1"" of type '" "iDynTree::RotationRaw *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_minus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialMomentum_minus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialMomentum_minus" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg2 = reinterpret_cast< iDynTree::RotationRaw * >(argp2); - result = (iDynTree::RotationRaw *) &(arg1)->changeRefOrientFrame((iDynTree::RotationRaw const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::SpatialMomentum const *)arg1)->operator -((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32934,37 +31251,23 @@ int _wrap_RotationRaw_changeRefOrientFrame(int resc, mxArray *resv[], int argc, } -int _wrap_RotationRaw_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = 0 ; - iDynTree::RotationRaw *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialMomentum_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("RotationRaw_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialMomentum_uminus",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_compose" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_compose" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); - } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_compose" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_compose" "', argument " "2"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialMomentum_uminus" "', argument " "1"" of type '" "iDynTree::SpatialMomentum const *""'"); } - arg2 = reinterpret_cast< iDynTree::RotationRaw * >(argp2); - result = iDynTree::RotationRaw::compose((iDynTree::RotationRaw const &)*arg1,(iDynTree::RotationRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); + result = ((iDynTree::SpatialMomentum const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32972,26 +31275,26 @@ int _wrap_RotationRaw_compose(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_RotationRaw_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = 0 ; - void *argp1 ; +int _wrap_delete_SpatialMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMomentum *arg1 = (iDynTree::SpatialMomentum *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; - if (!SWIG_check_num_args("RotationRaw_inverse2",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SpatialMomentum",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_inverse2" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialMomentum" "', argument " "1"" of type '" "iDynTree::SpatialMomentum *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_inverse2" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - result = iDynTree::RotationRaw::inverse2((iDynTree::RotationRaw const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -32999,34 +31302,54 @@ int _wrap_RotationRaw_inverse2(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_RotationRaw_changeCoordFrameOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; - iDynTree::PositionRaw *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::SpatialAcc *result = 0 ; + + if (!SWIG_check_num_args("new_SpatialAcc",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_SpatialAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinAcceleration *arg1 = 0 ; + iDynTree::AngAcceleration *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::PositionRaw result; + iDynTree::SpatialAcc *result = 0 ; - if (!SWIG_check_num_args("RotationRaw_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialAcc",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::RotationRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::LinAcceleration const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::LinAcceleration const &""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__PositionRaw, 0 ); + arg1 = reinterpret_cast< iDynTree::LinAcceleration * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialAcc" "', argument " "2"" of type '" "iDynTree::AngAcceleration const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::PositionRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "2"" of type '" "iDynTree::AngAcceleration const &""'"); } - arg2 = reinterpret_cast< iDynTree::PositionRaw * >(argp2); - result = ((iDynTree::RotationRaw const *)arg1)->changeCoordFrameOf((iDynTree::PositionRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::PositionRaw(static_cast< const iDynTree::PositionRaw& >(result))), SWIGTYPE_p_iDynTree__PositionRaw, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::AngAcceleration * >(argp2); + result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::LinAcceleration const &)*arg1,(iDynTree::AngAcceleration const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33034,34 +31357,26 @@ int _wrap_RotationRaw_changeCoordFrameOf__SWIG_0(int resc, mxArray *resv[], int } -int _wrap_RotationRaw_changeCoordFrameOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; - iDynTree::ClassicalAcc *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialMotionVector *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc result; + iDynTree::SpatialAcc *result = 0 ; - if (!SWIG_check_num_args("RotationRaw_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::RotationRaw const *""'"); - } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp2); - result = ((iDynTree::RotationRaw const *)arg1)->changeCoordFrameOf((iDynTree::ClassicalAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp1); + result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::SpatialMotionVector const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33069,34 +31384,26 @@ int _wrap_RotationRaw_changeCoordFrameOf__SWIG_1(int resc, mxArray *resv[], int } -int _wrap_RotationRaw_changeCoordFrameOf__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; - iDynTree::RotationalInertiaRaw *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SpatialAcc__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialAcc *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw result; + iDynTree::SpatialAcc *result = 0 ; - if (!SWIG_check_num_args("RotationRaw_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SpatialAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::RotationRaw const *""'"); - } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RotationRaw_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg2 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp2); - result = ((iDynTree::RotationRaw const *)arg1)->changeCoordFrameOf((iDynTree::RotationalInertiaRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::RotationalInertiaRaw(static_cast< const iDynTree::RotationalInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); + result = (iDynTree::SpatialAcc *)new iDynTree::SpatialAcc((iDynTree::SpatialAcc const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33104,76 +31411,81 @@ int _wrap_RotationRaw_changeCoordFrameOf__SWIG_2(int resc, mxArray *resv[], int } -int _wrap_RotationRaw_changeCoordFrameOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_SpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SpatialAcc__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__PositionRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_RotationRaw_changeCoordFrameOf__SWIG_0(resc,resv,argc,argv); - } + return _wrap_new_SpatialAcc__SWIG_3(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_RotationRaw_changeCoordFrameOf__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_SpatialAcc__SWIG_2(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationRaw, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_RotationRaw_changeCoordFrameOf__SWIG_2(resc,resv,argc,argv); + return _wrap_new_SpatialAcc__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'RotationRaw_changeCoordFrameOf'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialAcc'." " Possible C/C++ prototypes are:\n" - " iDynTree::RotationRaw::changeCoordFrameOf(iDynTree::PositionRaw const &) const\n" - " iDynTree::RotationRaw::changeCoordFrameOf(iDynTree::ClassicalAcc const &) const\n" - " iDynTree::RotationRaw::changeCoordFrameOf(iDynTree::RotationalInertiaRaw const &) const\n"); + " iDynTree::SpatialAcc::SpatialAcc()\n" + " iDynTree::SpatialAcc::SpatialAcc(iDynTree::LinAcceleration const &,iDynTree::AngAcceleration const &)\n" + " iDynTree::SpatialAcc::SpatialAcc(iDynTree::SpatialMotionVector const &)\n" + " iDynTree::SpatialAcc::SpatialAcc(iDynTree::SpatialAcc const &)\n"); return 1; } -int _wrap_RotationRaw_RotX(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_SpatialAcc_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("RotationRaw_RotX",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialAcc_plus",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "RotationRaw_RotX" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - result = iDynTree::RotationRaw::RotX(arg1); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_plus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialAcc_plus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialAcc_plus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::SpatialAcc const *)arg1)->operator +((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33181,23 +31493,34 @@ int _wrap_RotationRaw_RotX(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_RotationRaw_RotY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_SpatialAcc_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("RotationRaw_RotY",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialAcc_minus",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "RotationRaw_RotY" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - result = iDynTree::RotationRaw::RotY(arg1); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_minus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialAcc_minus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialAcc_minus" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::SpatialAcc const *)arg1)->operator -((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33205,23 +31528,23 @@ int _wrap_RotationRaw_RotY(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_RotationRaw_RotZ(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_SpatialAcc_uminus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("RotationRaw_RotZ",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialAcc_uminus",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "RotationRaw_RotZ" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - result = iDynTree::RotationRaw::RotZ(arg1); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialAcc_uminus" "', argument " "1"" of type '" "iDynTree::SpatialAcc const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); + result = ((iDynTree::SpatialAcc const *)arg1)->operator -(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33229,39 +31552,175 @@ int _wrap_RotationRaw_RotZ(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_RotationRaw_RPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; +int _wrap_delete_SpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialAcc *arg1 = (iDynTree::SpatialAcc *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_SpatialAcc",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialAcc" "', argument " "1"" of type '" "iDynTree::SpatialAcc *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialAcc * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_ClassicalAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::ClassicalAcc *result = 0 ; + + if (!SWIG_check_num_args("new_ClassicalAcc",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_ClassicalAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + unsigned int val2 ; int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::ClassicalAcc *result = 0 ; - if (!SWIG_check_num_args("RotationRaw_RPY",argc,3,3,0)) { + if (!SWIG_check_num_args("new_ClassicalAcc",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "RotationRaw_RPY" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "double const *""'"); + } + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RotationRaw_RPY" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "RotationRaw_RPY" "', argument " "3"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_ClassicalAcc" "', argument " "2"" of type '" "unsigned int""'"); } - arg3 = static_cast< double >(val3); - result = iDynTree::RotationRaw::RPY(arg1,arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + arg2 = static_cast< unsigned int >(val2); + result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_ClassicalAcc__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ClassicalAcc *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::ClassicalAcc *result = 0 ; + + if (!SWIG_check_num_args("new_ClassicalAcc",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const &""'"); + } + arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); + result = (iDynTree::ClassicalAcc *)new iDynTree::ClassicalAcc((iDynTree::ClassicalAcc const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_ClassicalAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_ClassicalAcc__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ClassicalAcc__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_ClassicalAcc__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ClassicalAcc'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ClassicalAcc::ClassicalAcc()\n" + " iDynTree::ClassicalAcc::ClassicalAcc(double const *,unsigned int const)\n" + " iDynTree::ClassicalAcc::ClassicalAcc(iDynTree::ClassicalAcc const &)\n"); + return 1; +} + + +int _wrap_ClassicalAcc_changeCoordFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; + iDynTree::Rotation *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + iDynTree::ClassicalAcc *result = 0 ; + + if (!SWIG_check_num_args("ClassicalAcc_changeCoordFrame",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); + } + arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_changeCoordFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (iDynTree::ClassicalAcc *) &(arg1)->changeCoordFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33269,16 +31728,16 @@ int _wrap_RotationRaw_RPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_RotationRaw_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ClassicalAcc_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::RotationRaw result; + iDynTree::ClassicalAcc result; - if (!SWIG_check_num_args("RotationRaw_Identity",argc,0,0,0)) { + if (!SWIG_check_num_args("ClassicalAcc_Zero",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = iDynTree::RotationRaw::Identity(); - _out = SWIG_NewPointerObj((new iDynTree::RotationRaw(static_cast< const iDynTree::RotationRaw& >(result))), SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_OWN | 0 ); + result = iDynTree::ClassicalAcc::Zero(); + _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33286,23 +31745,44 @@ int _wrap_RotationRaw_Identity(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_RotationRaw_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; +int _wrap_ClassicalAcc_fromSpatial(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + iDynTree::Twist *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("RotationRaw_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("ClassicalAcc_fromSpatial",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_toString" "', argument " "1"" of type '" "iDynTree::RotationRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_fromSpatial" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - result = ((iDynTree::RotationRaw const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_fromSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_fromSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ClassicalAcc_fromSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_fromSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); + (arg1)->fromSpatial((iDynTree::SpatialAcc const &)*arg2,(iDynTree::Twist const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33310,23 +31790,44 @@ int _wrap_RotationRaw_toString(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_RotationRaw_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; +int _wrap_ClassicalAcc_toSpatial(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + iDynTree::Twist *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("RotationRaw_display",argc,1,1,0)) { + if (!SWIG_check_num_args("ClassicalAcc_toSpatial",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RotationRaw_display" "', argument " "1"" of type '" "iDynTree::RotationRaw const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ClassicalAcc_toSpatial" "', argument " "1"" of type '" "iDynTree::ClassicalAcc const *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - result = ((iDynTree::RotationRaw const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ClassicalAcc_toSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_toSpatial" "', argument " "2"" of type '" "iDynTree::SpatialAcc &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ClassicalAcc_toSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ClassicalAcc_toSpatial" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); + ((iDynTree::ClassicalAcc const *)arg1)->toSpatial(*arg2,(iDynTree::Twist const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33334,22 +31835,22 @@ int _wrap_RotationRaw_display(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_delete_RotationRaw(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = (iDynTree::RotationRaw *) 0 ; +int _wrap_delete_ClassicalAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ClassicalAcc *arg1 = (iDynTree::ClassicalAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_RotationRaw",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_ClassicalAcc",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationRaw, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_RotationRaw" "', argument " "1"" of type '" "iDynTree::RotationRaw *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ClassicalAcc" "', argument " "1"" of type '" "iDynTree::ClassicalAcc *""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); + arg1 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp1); if (is_owned) { delete arg1; } @@ -33361,16 +31862,16 @@ int _wrap_delete_RotationRaw(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_new_Rotation__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Direction__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Direction *result = 0 ; - if (!SWIG_check_num_args("new_Rotation",argc,0,0,0)) { + if (!SWIG_check_num_args("new_Direction",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::Rotation *)new iDynTree::Rotation(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); + result = (iDynTree::Direction *)new iDynTree::Direction(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33378,87 +31879,39 @@ int _wrap_new_Rotation__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Rotation__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Direction__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double arg1 ; double arg2 ; double arg3 ; - double arg4 ; - double arg5 ; - double arg6 ; - double arg7 ; - double arg8 ; - double arg9 ; double val1 ; int ecode1 = 0 ; double val2 ; int ecode2 = 0 ; double val3 ; int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - double val5 ; - int ecode5 = 0 ; - double val6 ; - int ecode6 = 0 ; - double val7 ; - int ecode7 = 0 ; - double val8 ; - int ecode8 = 0 ; - double val9 ; - int ecode9 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Direction *result = 0 ; - if (!SWIG_check_num_args("new_Rotation",argc,9,9,0)) { + if (!SWIG_check_num_args("new_Direction",argc,3,3,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_double(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Rotation" "', argument " "1"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Direction" "', argument " "1"" of type '" "double""'"); } arg1 = static_cast< double >(val1); ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Rotation" "', argument " "2"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Direction" "', argument " "2"" of type '" "double""'"); } arg2 = static_cast< double >(val2); ecode3 = SWIG_AsVal_double(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Rotation" "', argument " "3"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Direction" "', argument " "3"" of type '" "double""'"); } arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "new_Rotation" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - ecode5 = SWIG_AsVal_double(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "new_Rotation" "', argument " "5"" of type '" "double""'"); - } - arg5 = static_cast< double >(val5); - ecode6 = SWIG_AsVal_double(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "new_Rotation" "', argument " "6"" of type '" "double""'"); - } - arg6 = static_cast< double >(val6); - ecode7 = SWIG_AsVal_double(argv[6], &val7); - if (!SWIG_IsOK(ecode7)) { - SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "new_Rotation" "', argument " "7"" of type '" "double""'"); - } - arg7 = static_cast< double >(val7); - ecode8 = SWIG_AsVal_double(argv[7], &val8); - if (!SWIG_IsOK(ecode8)) { - SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "new_Rotation" "', argument " "8"" of type '" "double""'"); - } - arg8 = static_cast< double >(val8); - ecode9 = SWIG_AsVal_double(argv[8], &val9); - if (!SWIG_IsOK(ecode9)) { - SWIG_exception_fail(SWIG_ArgError(ecode9), "in method '" "new_Rotation" "', argument " "9"" of type '" "double""'"); - } - arg9 = static_cast< double >(val9); - result = (iDynTree::Rotation *)new iDynTree::Rotation(arg1,arg2,arg3,arg4,arg5,arg6,arg7,arg8,arg9); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); + result = (iDynTree::Direction *)new iDynTree::Direction(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33466,26 +31919,26 @@ int _wrap_new_Rotation__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Rotation__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::RotationRaw *arg1 = 0 ; +int _wrap_new_Direction__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Direction *result = 0 ; - if (!SWIG_check_num_args("new_Rotation",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Direction",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationRaw, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Direction" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::RotationRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Direction" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } - arg1 = reinterpret_cast< iDynTree::RotationRaw * >(argp1); - result = (iDynTree::Rotation *)new iDynTree::Rotation((iDynTree::RotationRaw const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + result = (iDynTree::Direction *)new iDynTree::Direction((iDynTree::Direction const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33493,56 +31946,31 @@ int _wrap_new_Rotation__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Rotation__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = 0 ; - void *argp1 ; +int _wrap_new_Direction__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Direction *result = 0 ; - if (!SWIG_check_num_args("new_Rotation",argc,1,1,0)) { + if (!SWIG_check_num_args("new_Direction",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = (iDynTree::Rotation *)new iDynTree::Rotation((iDynTree::Rotation const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Rotation__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Rotation *result = 0 ; - - if (!SWIG_check_num_args("new_Rotation",argc,1,1,0)) { - SWIG_fail; - } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); - } + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Direction" "', argument " "1"" of type '" "double const *""'"); } - result = (iDynTree::Rotation *)new iDynTree::Rotation(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Direction" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + result = (iDynTree::Direction *)new iDynTree::Direction((double const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33550,38 +31978,35 @@ int _wrap_new_Rotation__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_Rotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_Direction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_Rotation__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Direction__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Rotation__SWIG_3(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Rotation__SWIG_2(resc,resv,argc,argv); + return _wrap_new_Direction__SWIG_2(resc,resv,argc,argv); } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Rotation__SWIG_4(resc,resv,argc,argv); + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Direction__SWIG_3(resc,resv,argc,argv); + } } } - if (argc == 9) { + if (argc == 3) { int _v; { int res = SWIG_AsVal_double(argv[0], NULL); @@ -33598,87 +32023,46 @@ int _wrap_new_Rotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { _v = SWIG_CheckState(res); } if (_v) { - { - int res = SWIG_AsVal_double(argv[3], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[4], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[5], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[6], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[7], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_double(argv[8], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_Rotation__SWIG_1(resc,resv,argc,argv); - } - } - } - } - } - } + return _wrap_new_Direction__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Rotation'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Direction'." " Possible C/C++ prototypes are:\n" - " iDynTree::Rotation::Rotation()\n" - " iDynTree::Rotation::Rotation(double,double,double,double,double,double,double,double,double)\n" - " iDynTree::Rotation::Rotation(iDynTree::RotationRaw const &)\n" - " iDynTree::Rotation::Rotation(iDynTree::Rotation const &)\n" - " iDynTree::Rotation::Rotation(iDynTree::MatrixView< double const >)\n"); + " iDynTree::Direction::Direction()\n" + " iDynTree::Direction::Direction(double,double,double)\n" + " iDynTree::Direction::Direction(iDynTree::Direction const &)\n" + " iDynTree::Direction::Direction(double const *,unsigned int const)\n"); return 1; } -int _wrap_Rotation_changeOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Direction_Normalize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeOrientFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_Normalize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeOrientFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_Normalize" "', argument " "1"" of type '" "iDynTree::Direction *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (iDynTree::Rotation *) &(arg1)->changeOrientFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Direction_Normalize" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + (arg1)->Normalize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33686,34 +32070,22 @@ int _wrap_Rotation_changeOrientFrame(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_Rotation_changeRefOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Direction_Normalize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeRefOrientFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_Normalize",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeRefOrientFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_Normalize" "', argument " "1"" of type '" "iDynTree::Direction *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (iDynTree::Rotation *) &(arg1)->changeRefOrientFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + (arg1)->Normalize(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33721,34 +32093,76 @@ int _wrap_Rotation_changeRefOrientFrame(int resc, mxArray *resv[], int argc, mxA } -int _wrap_Rotation_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Direction_Normalize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Direction_Normalize__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Direction_Normalize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Direction_Normalize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Direction::Normalize(double)\n" + " iDynTree::Direction::Normalize()\n"); + return 1; +} + + +int _wrap_Direction_isParallel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; + iDynTree::Direction *arg2 = 0 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + bool result; - if (!SWIG_check_num_args("Rotation_changeCoordinateFrame",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_isParallel",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordinateFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_isParallel" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Direction_isParallel" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Direction_isParallel" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = (iDynTree::Rotation *) &(arg1)->changeCoordinateFrame((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Direction_isParallel" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)((iDynTree::Direction const *)arg1)->isParallel((iDynTree::Direction const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33756,37 +32170,42 @@ int _wrap_Rotation_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mx } -int _wrap_Rotation_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = 0 ; - iDynTree::Rotation *arg2 = 0 ; - void *argp1 ; +int _wrap_Direction_isPerpendicular(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; + iDynTree::Direction *arg2 = 0 ; + double arg3 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Rotation result; + bool result; - if (!SWIG_check_num_args("Rotation_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_isPerpendicular",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_compose" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_compose" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_isPerpendicular" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_compose" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Direction_isPerpendicular" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_compose" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Direction_isPerpendicular" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = iDynTree::Rotation::compose((iDynTree::Rotation const &)*arg1,(iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Direction_isPerpendicular" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)((iDynTree::Direction const *)arg1)->isPerpendicular((iDynTree::Direction const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33794,26 +32213,23 @@ int _wrap_Rotation_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Rotation_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = 0 ; - void *argp1 ; +int _wrap_Direction_reverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Rotation result; + iDynTree::Direction result; - if (!SWIG_check_num_args("Rotation_inverse2",argc,1,1,0)) { + if (!SWIG_check_num_args("Direction_reverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_inverse2" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_inverse2" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_reverse" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = iDynTree::Rotation::inverse2((iDynTree::Rotation const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + result = ((iDynTree::Direction const *)arg1)->reverse(); + _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33821,34 +32237,23 @@ int _wrap_Rotation_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Rotation_changeCoordFrameOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_Direction_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Position result; + std::string result; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_toString" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + result = ((iDynTree::Direction const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33856,34 +32261,23 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; +int _wrap_Direction_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + std::string result; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Direction_display" "', argument " "1"" of type '" "iDynTree::Direction const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + result = ((iDynTree::Direction const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33891,34 +32285,16 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_Direction_Default(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::Direction result; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Direction_Default",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = iDynTree::Direction::Default(); + _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33926,34 +32302,26 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_2(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_delete_Direction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = (iDynTree::Direction *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Twist result; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Direction",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Direction" "', argument " "1"" of type '" "iDynTree::Direction *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33961,34 +32329,16 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_3(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_Axis__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::Axis *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Axis",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::Axis *)new iDynTree::Axis(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -33996,34 +32346,37 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_4(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_Axis__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = 0 ; + iDynTree::Position *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + iDynTree::Axis *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Axis",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Axis" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (iDynTree::Axis *)new iDynTree::Axis((iDynTree::Direction const &)*arg1,(iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34031,34 +32384,26 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_5(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Wrench *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_Axis__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + iDynTree::Axis *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Axis",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Axis, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Axis const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Axis" "', argument " "1"" of type '" "iDynTree::Axis const &""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = (iDynTree::Axis *)new iDynTree::Axis((iDynTree::Axis const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Axis, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34066,69 +32411,60 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_6(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Direction *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::Direction result; - - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); +int _wrap_new_Axis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Axis__SWIG_0(resc,resv,argc,argv); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Axis__SWIG_2(resc,resv,argc,argv); + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Axis__SWIG_1(resc,resv,argc,argv); + } + } } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Direction const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Axis'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Axis::Axis()\n" + " iDynTree::Axis::Axis(iDynTree::Direction const &,iDynTree::Position const &)\n" + " iDynTree::Axis::Axis(iDynTree::Axis const &)\n"); return 1; } -int _wrap_Rotation_changeCoordFrameOf__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Axis *arg2 = 0 ; +int _wrap_Axis_getDirection(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Axis result; + iDynTree::Direction *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getDirection",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getDirection" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Axis const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = (iDynTree::Direction *) &((iDynTree::Axis const *)arg1)->getDirection(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Direction, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34136,34 +32472,23 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_8(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::ClassicalAcc *arg2 = 0 ; +int _wrap_Axis_getOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getOrigin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getOrigin" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::ClassicalAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = (iDynTree::Position *) &((iDynTree::Axis const *)arg1)->getOrigin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34171,34 +32496,33 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_9(int resc, mxArray *resv[], int arg } -int _wrap_Rotation_changeCoordFrameOf__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::RotationalInertiaRaw *arg2 = 0 ; +int _wrap_Axis_setDirection(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + iDynTree::Direction *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw result; - if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_setDirection",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_setDirection" "', argument " "1"" of type '" "iDynTree::Axis *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_setDirection" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_setDirection" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - arg2 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::RotationalInertiaRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::RotationalInertiaRaw(static_cast< const iDynTree::RotationalInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + (arg1)->setDirection((iDynTree::Direction const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34206,207 +32530,33 @@ int _wrap_Rotation_changeCoordFrameOf__SWIG_10(int resc, mxArray *resv[], int ar } -int _wrap_Rotation_changeCoordFrameOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_3(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_5(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_4(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_6(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_2(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_7(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_8(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_9(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_changeCoordFrameOf__SWIG_10(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_changeCoordFrameOf'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Position const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialForceVector const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Twist const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialAcc const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialMomentum const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Wrench const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Direction const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Axis const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::ClassicalAcc const &) const\n" - " iDynTree::Rotation::changeCoordFrameOf(iDynTree::RotationalInertiaRaw const &) const\n"); - return 1; -} - - -int _wrap_Rotation_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_Axis_setOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Rotation result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_setOrigin",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_setOrigin" "', argument " "1"" of type '" "iDynTree::Axis *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_setOrigin" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_setOrigin" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Rotation const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + (arg1)->setOrigin((iDynTree::Position const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34414,23 +32564,31 @@ int _wrap_Rotation_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_Axis_getRotationTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Rotation result; + iDynTree::Transform result; - if (!SWIG_check_num_args("Rotation_inverse",argc,1,1,0)) { + if (!SWIG_check_num_args("Axis_getRotationTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_inverse" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTransform" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->inverse(); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTransform" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getRotationTransform(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34438,34 +32596,31 @@ int _wrap_Rotation_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Rotation_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_Axis_getRotationTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position result; + iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getRotationTransformDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTransformDerivative" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTransformDerivative" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getRotationTransformDerivative(arg2); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34473,34 +32628,31 @@ int _wrap_Rotation_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_Axis_getRotationTwist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::Twist result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getRotationTwist",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationTwist" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationTwist" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getRotationTwist(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34508,34 +32660,31 @@ int _wrap_Rotation_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_Axis_getRotationSpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Twist result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getRotationSpatialAcc",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getRotationSpatialAcc" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getRotationSpatialAcc" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getRotationSpatialAcc(arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34543,34 +32692,31 @@ int _wrap_Rotation_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Wrench *arg2 = 0 ; +int _wrap_Axis_getTranslationTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Wrench result; + iDynTree::Transform result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getTranslationTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTransform" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTransform" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getTranslationTransform(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34578,69 +32724,63 @@ int _wrap_Rotation_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Direction *arg2 = 0 ; +int _wrap_Axis_getTranslationTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Direction result; + iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getTranslationTransformDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTransformDerivative" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Direction const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_mtimes__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Axis *arg2 = 0 ; + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTransformDerivative" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getTranslationTransformDerivative(arg2); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Axis_getTranslationTwist(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Axis result; + iDynTree::Twist result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getTranslationTwist",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationTwist" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Axis const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationTwist" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getTranslationTwist(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34648,33 +32788,30 @@ int _wrap_Rotation_mtimes__SWIG_6(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_Axis_getTranslationSpatialAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_getTranslationSpatialAcc",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_getTranslationSpatialAcc" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Axis_getTranslationSpatialAcc" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = ((iDynTree::Axis const *)arg1)->getTranslationSpatialAcc(arg2); _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -34683,34 +32820,42 @@ int _wrap_Rotation_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; +int _wrap_Axis_isParallel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; + iDynTree::Axis *arg2 = 0 ; + double arg3 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + bool result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_isParallel",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_isParallel" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Axis_isParallel" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Axis_isParallel" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Axis_isParallel" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = (bool)((iDynTree::Axis const *)arg1)->isParallel((iDynTree::Axis const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34718,34 +32863,23 @@ int _wrap_Rotation_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::ClassicalAcc *arg2 = 0 ; +int _wrap_Axis_reverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ClassicalAcc result; + iDynTree::Axis result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_reverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_reverse" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::ClassicalAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = ((iDynTree::Axis const *)arg1)->reverse(); + _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34753,34 +32887,23 @@ int _wrap_Rotation_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::RotationalInertiaRaw *arg2 = 0 ; +int _wrap_Axis_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::RotationalInertiaRaw result; + std::string result; - if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("Axis_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::RotationalInertiaRaw const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_toString" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg2 = reinterpret_cast< iDynTree::RotationalInertiaRaw * >(argp2); - result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::RotationalInertiaRaw const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::RotationalInertiaRaw(static_cast< const iDynTree::RotationalInertiaRaw& >(result))), SWIGTYPE_p_iDynTree__RotationalInertiaRaw, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = ((iDynTree::Axis const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34788,196 +32911,23 @@ int _wrap_Rotation_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Rotation_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_4(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_3(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_8(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_5(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_6(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_7(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_2(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_9(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__RotationalInertiaRaw, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_mtimes__SWIG_10(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_mtimes'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Rotation::operator *(iDynTree::Rotation const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::Position const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::SpatialForceVector const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::Twist const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::Wrench const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::Direction const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::Axis const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::SpatialAcc const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::SpatialMomentum const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::ClassicalAcc const &) const\n" - " iDynTree::Rotation::operator *(iDynTree::RotationalInertiaRaw const &) const\n"); - return 1; -} - - -int _wrap_Rotation_log(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_Axis_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::AngularMotionVector3 result; + std::string result; - if (!SWIG_check_num_args("Rotation_log",argc,1,1,0)) { + if (!SWIG_check_num_args("Axis_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_log" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Axis_display" "', argument " "1"" of type '" "iDynTree::Axis const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->log(); - _out = SWIG_NewPointerObj((new iDynTree::AngularMotionVector3(static_cast< const iDynTree::AngularMotionVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + result = ((iDynTree::Axis const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -34985,32 +32935,25 @@ int _wrap_Rotation_log(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_fromQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Vector4 *arg2 = 0 ; +int _wrap_delete_Axis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Axis *arg1 = (iDynTree::Axis *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Rotation_fromQuaternion",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Axis",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_fromQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_fromQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Axis" "', argument " "1"" of type '" "iDynTree::Axis *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_fromQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 const &""'"); + arg1 = reinterpret_cast< iDynTree::Axis * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Vector4 * >(argp2); - (arg1)->fromQuaternion((iDynTree::Vector4 const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -35019,55 +32962,16 @@ int _wrap_Rotation_fromQuaternion(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Rotation_getRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - double *arg2 = 0 ; - double *arg3 = 0 ; - double *arg4 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; +int _wrap_new_RotationalInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::RotationalInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_getRPY",argc,4,4,0)) { + if (!SWIG_check_num_args("new_RotationalInertia",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getRPY" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getRPY" "', argument " "2"" of type '" "double &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "2"" of type '" "double &""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Rotation_getRPY" "', argument " "3"" of type '" "double &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "3"" of type '" "double &""'"); - } - arg3 = reinterpret_cast< double * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Rotation_getRPY" "', argument " "4"" of type '" "double &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "4"" of type '" "double &""'"); - } - arg4 = reinterpret_cast< double * >(argp4); - ((iDynTree::Rotation const *)arg1)->getRPY(*arg2,*arg3,*arg4); - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::RotationalInertia *)new iDynTree::RotationalInertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35075,23 +32979,39 @@ int _wrap_Rotation_getRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Rotation_asRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_new_RotationalInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + unsigned int arg3 ; void *argp1 = 0 ; int res1 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; + unsigned int val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Vector3 result; + iDynTree::RotationalInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_asRPY",argc,1,1,0)) { + if (!SWIG_check_num_args("new_RotationalInertia",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_asRPY" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationalInertia" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->asRPY(); - _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_RotationalInertia" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_RotationalInertia" "', argument " "3"" of type '" "unsigned int""'"); + } + arg3 = static_cast< unsigned int >(val3); + result = (iDynTree::RotationalInertia *)new iDynTree::RotationalInertia((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35099,34 +33019,26 @@ int _wrap_Rotation_asRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_getQuaternion__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - iDynTree::Vector4 *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_RotationalInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RotationalInertia *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::RotationalInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_getQuaternion",argc,2,2,0)) { + if (!SWIG_check_num_args("new_RotationalInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__RotationalInertia, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_RotationalInertia" "', argument " "1"" of type '" "iDynTree::RotationalInertia const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_RotationalInertia" "', argument " "1"" of type '" "iDynTree::RotationalInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector4 * >(argp2); - result = (bool)((iDynTree::Rotation const *)arg1)->getQuaternion(*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::RotationalInertia * >(argp1); + result = (iDynTree::RotationalInertia *)new iDynTree::RotationalInertia((iDynTree::RotationalInertia const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35134,144 +33046,87 @@ int _wrap_Rotation_getQuaternion__SWIG_0(int resc, mxArray *resv[], int argc, mx } -int _wrap_Rotation_getQuaternion__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - double *arg2 = 0 ; - double *arg3 = 0 ; - double *arg4 = 0 ; - double *arg5 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Rotation_getQuaternion",argc,5,5,0)) { - SWIG_fail; +int _wrap_new_RotationalInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_RotationalInertia__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__RotationalInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_RotationalInertia__SWIG_2(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "double &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "double &""'"); - } - arg2 = reinterpret_cast< double * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Rotation_getQuaternion" "', argument " "3"" of type '" "double &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "3"" of type '" "double &""'"); - } - arg3 = reinterpret_cast< double * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Rotation_getQuaternion" "', argument " "4"" of type '" "double &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "4"" of type '" "double &""'"); - } - arg4 = reinterpret_cast< double * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Rotation_getQuaternion" "', argument " "5"" of type '" "double &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "5"" of type '" "double &""'"); - } - arg5 = reinterpret_cast< double * >(argp5); - result = (bool)((iDynTree::Rotation const *)arg1)->getQuaternion(*arg2,*arg3,*arg4,*arg5); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_getQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_getQuaternion__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); } - } - } - if (argc == 5) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_double, 0); + { + int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Rotation_getQuaternion__SWIG_1(resc,resv,argc,argv); - } - } + } + if (_v) { + return _wrap_new_RotationalInertia__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_getQuaternion'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_RotationalInertia'." " Possible C/C++ prototypes are:\n" - " iDynTree::Rotation::getQuaternion(iDynTree::Vector4 &) const\n" - " iDynTree::Rotation::getQuaternion(double &,double &,double &,double &) const\n"); + " iDynTree::RotationalInertia::RotationalInertia()\n" + " iDynTree::RotationalInertia::RotationalInertia(double const *,unsigned int const,unsigned int const)\n" + " iDynTree::RotationalInertia::RotationalInertia(iDynTree::RotationalInertia const &)\n"); return 1; } -int _wrap_Rotation_asQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_RotationalInertia_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::RotationalInertia result; + + if (!SWIG_check_num_args("RotationalInertia_Zero",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = iDynTree::RotationalInertia::Zero(); + _out = SWIG_NewPointerObj((new iDynTree::RotationalInertia(static_cast< const iDynTree::RotationalInertia& >(result))), SWIGTYPE_p_iDynTree__RotationalInertia, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_RotationalInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RotationalInertia *arg1 = (iDynTree::RotationalInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Vector4 result; - if (!SWIG_check_num_args("Rotation_asQuaternion",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_RotationalInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RotationalInertia, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_asQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_RotationalInertia" "', argument " "1"" of type '" "iDynTree::RotationalInertia *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->asQuaternion(); - _out = SWIG_NewPointerObj((new iDynTree::Vector4(static_cast< const iDynTree::Vector4& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::RotationalInertia * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35279,23 +33134,16 @@ int _wrap_Rotation_asQuaternion(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Rotation_RotX(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_new_SpatialInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Rotation result; + iDynTree::SpatialInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_RotX",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialInertia",argc,0,0,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotX" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - result = iDynTree::Rotation::RotX(arg1); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35303,23 +33151,45 @@ int _wrap_Rotation_RotX(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_RotY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SpatialInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { double arg1 ; + iDynTree::Position *arg2 = 0 ; + iDynTree::RotationalInertia *arg3 = 0 ; double val1 ; int ecode1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::Rotation result; + iDynTree::SpatialInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_RotY",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialInertia",argc,3,3,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_double(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotY" "', argument " "1"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "double""'"); } arg1 = static_cast< double >(val1); - result = iDynTree::Rotation::RotY(arg1); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SpatialInertia" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__RotationalInertia, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_SpatialInertia" "', argument " "3"" of type '" "iDynTree::RotationalInertia const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "3"" of type '" "iDynTree::RotationalInertia const &""'"); + } + arg3 = reinterpret_cast< iDynTree::RotationalInertia * >(argp3); + result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia(arg1,(iDynTree::Position const &)*arg2,(iDynTree::RotationalInertia const &)*arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35327,23 +33197,26 @@ int _wrap_Rotation_RotY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_RotZ(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double val1 ; - int ecode1 = 0 ; +int _wrap_new_SpatialInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Rotation result; + iDynTree::SpatialInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_RotZ",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SpatialInertia",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotZ" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - result = iDynTree::Rotation::RotZ(arg1); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = (iDynTree::SpatialInertia *)new iDynTree::SpatialInertia((iDynTree::SpatialInertia const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35351,34 +33224,80 @@ int _wrap_Rotation_RotZ(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_RotAxis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = 0 ; - double arg2 ; +int _wrap_new_SpatialInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SpatialInertia__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialInertia__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__RotationalInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SpatialInertia__SWIG_1(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SpatialInertia'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SpatialInertia::SpatialInertia()\n" + " iDynTree::SpatialInertia::SpatialInertia(double const,iDynTree::Position const &,iDynTree::RotationalInertia const &)\n" + " iDynTree::SpatialInertia::SpatialInertia(iDynTree::SpatialInertia const &)\n"); + return 1; +} + + +int _wrap_SpatialInertia_combine(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = 0 ; + iDynTree::SpatialInertia *arg2 = 0 ; void *argp1 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Rotation result; + iDynTree::SpatialInertia result; - if (!SWIG_check_num_args("Rotation_RotAxis",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_combine",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotAxis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotAxis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_combine" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RotAxis" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - result = iDynTree::Rotation::RotAxis((iDynTree::Direction const &)*arg1,arg2); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_combine" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); + result = iDynTree::SpatialInertia::combine((iDynTree::SpatialInertia const &)*arg1,(iDynTree::SpatialInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35386,34 +33305,52 @@ int _wrap_Rotation_RotAxis(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Rotation_RotAxisDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Direction *arg1 = 0 ; +int _wrap_SpatialInertia_fromRotationalInertiaWrtCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; double arg2 ; - void *argp1 ; + iDynTree::Position *arg3 = 0 ; + iDynTree::RotationalInertia *arg4 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; double val2 ; int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("Rotation_RotAxisDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_fromRotationalInertiaWrtCenterOfMass",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotAxisDerivative" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotAxisDerivative" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); } - arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RotAxisDerivative" "', argument " "2"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "2"" of type '" "double""'"); } arg2 = static_cast< double >(val2); - result = iDynTree::Rotation::RotAxisDerivative((iDynTree::Direction const &)*arg1,arg2); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "3"" of type '" "iDynTree::Position const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "3"" of type '" "iDynTree::Position const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Position * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__RotationalInertia, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "4"" of type '" "iDynTree::RotationalInertia const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_fromRotationalInertiaWrtCenterOfMass" "', argument " "4"" of type '" "iDynTree::RotationalInertia const &""'"); + } + arg4 = reinterpret_cast< iDynTree::RotationalInertia * >(argp4); + (arg1)->fromRotationalInertiaWrtCenterOfMass(arg2,(iDynTree::Position const &)*arg3,(iDynTree::RotationalInertia const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35421,39 +33358,23 @@ int _wrap_Rotation_RotAxisDerivative(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_Rotation_RPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_SpatialInertia_getMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Rotation result; + double result; - if (!SWIG_check_num_args("Rotation_RPY",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialInertia_getMass",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPY" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPY" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPY" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = iDynTree::Rotation::RPY(arg1,arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getMass" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = (double)((iDynTree::SpatialInertia const *)arg1)->getMass(); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35461,39 +33382,23 @@ int _wrap_Rotation_RPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Rotation_RPYRightTrivializedDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_SpatialInertia_getCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::Position result; - if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivative",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialInertia_getCenterOfMass",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = iDynTree::Rotation::RPYRightTrivializedDerivative(arg1,arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = ((iDynTree::SpatialInertia const *)arg1)->getCenterOfMass(); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35501,63 +33406,23 @@ int _wrap_Rotation_RPYRightTrivializedDerivative(int resc, mxArray *resv[], int } -int _wrap_Rotation_RPYRightTrivializedDerivativeRateOfChange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double arg4 ; - double arg5 ; - double arg6 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - double val5 ; - int ecode5 = 0 ; - double val6 ; - int ecode6 = 0 ; +int _wrap_SpatialInertia_getRotationalInertiaWrtFrameOrigin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::RotationalInertia *result = 0 ; - if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeRateOfChange",argc,6,6,0)) { + if (!SWIG_check_num_args("SpatialInertia_getRotationalInertiaWrtFrameOrigin",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - ecode5 = SWIG_AsVal_double(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "5"" of type '" "double""'"); - } - arg5 = static_cast< double >(val5); - ecode6 = SWIG_AsVal_double(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "6"" of type '" "double""'"); - } - arg6 = static_cast< double >(val6); - result = iDynTree::Rotation::RPYRightTrivializedDerivativeRateOfChange(arg1,arg2,arg3,arg4,arg5,arg6); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getRotationalInertiaWrtFrameOrigin" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = (iDynTree::RotationalInertia *) &((iDynTree::SpatialInertia const *)arg1)->getRotationalInertiaWrtFrameOrigin(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RotationalInertia, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35565,39 +33430,23 @@ int _wrap_Rotation_RPYRightTrivializedDerivativeRateOfChange(int resc, mxArray * } -int _wrap_Rotation_RPYRightTrivializedDerivativeInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; +int _wrap_SpatialInertia_getRotationalInertiaWrtCenterOfMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::RotationalInertia result; - if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeInverse",argc,3,3,0)) { + if (!SWIG_check_num_args("SpatialInertia_getRotationalInertiaWrtCenterOfMass",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - result = iDynTree::Rotation::RPYRightTrivializedDerivativeInverse(arg1,arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getRotationalInertiaWrtCenterOfMass" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = ((iDynTree::SpatialInertia const *)arg1)->getRotationalInertiaWrtCenterOfMass(); + _out = SWIG_NewPointerObj((new iDynTree::RotationalInertia(static_cast< const iDynTree::RotationalInertia& >(result))), SWIGTYPE_p_iDynTree__RotationalInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35605,140 +33454,34 @@ int _wrap_Rotation_RPYRightTrivializedDerivativeInverse(int resc, mxArray *resv[ } -int _wrap_Rotation_RPYRightTrivializedDerivativeInverseRateOfChange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double arg4 ; - double arg5 ; - double arg6 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - double val5 ; - int ecode5 = 0 ; - double val6 ; - int ecode6 = 0 ; +int _wrap_SpatialInertia_multiply(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeInverseRateOfChange",argc,6,6,0)) { + if (!SWIG_check_num_args("SpatialInertia_multiply",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - ecode5 = SWIG_AsVal_double(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "5"" of type '" "double""'"); - } - arg5 = static_cast< double >(val5); - ecode6 = SWIG_AsVal_double(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "6"" of type '" "double""'"); - } - arg6 = static_cast< double >(val6); - result = iDynTree::Rotation::RPYRightTrivializedDerivativeInverseRateOfChange(arg1,arg2,arg3,arg4,arg5,arg6); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_QuaternionRightTrivializedDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Vector4 arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - SwigValueWrapper< iDynTree::MatrixFixSize< 4,3 > > result; - - if (!SWIG_check_num_args("Rotation_QuaternionRightTrivializedDerivative",argc,1,1,0)) { - SWIG_fail; - } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_QuaternionRightTrivializedDerivative" "', argument " "1"" of type '" "iDynTree::Vector4""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_QuaternionRightTrivializedDerivative" "', argument " "1"" of type '" "iDynTree::Vector4""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::Vector4 * >(argp1)); - } - } - result = iDynTree::Rotation::QuaternionRightTrivializedDerivative(arg1); - _out = SWIG_NewPointerObj((new iDynTree::MatrixFixSize< 4,3 >(static_cast< const iDynTree::MatrixFixSize< 4,3 >& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_3_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_QuaternionRightTrivializedDerivativeInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Vector4 arg1 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - SwigValueWrapper< iDynTree::MatrixFixSize< 3,4 > > result; - - if (!SWIG_check_num_args("Rotation_QuaternionRightTrivializedDerivativeInverse",argc,1,1,0)) { - SWIG_fail; + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_multiply" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - { - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_QuaternionRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "iDynTree::Vector4""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_QuaternionRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "iDynTree::Vector4""'"); - } else { - arg1 = *(reinterpret_cast< iDynTree::Vector4 * >(argp1)); - } + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_multiply" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - result = iDynTree::Rotation::QuaternionRightTrivializedDerivativeInverse(arg1); - _out = SWIG_NewPointerObj((new iDynTree::MatrixFixSize< 3,4 >(static_cast< const iDynTree::MatrixFixSize< 3,4 >& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_4_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::Rotation result; - - if (!SWIG_check_num_args("Rotation_Identity",argc,0,0,0)) { - SWIG_fail; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_multiply" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - (void)argv; - result = iDynTree::Rotation::Identity(); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->multiply((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35746,26 +33489,22 @@ int _wrap_Rotation_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Rotation_RotationFromQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Vector4 *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Rotation result; - if (!SWIG_check_num_args("Rotation_RotationFromQuaternion",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_zero",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotationFromQuaternion" "', argument " "1"" of type '" "iDynTree::Vector4 const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotationFromQuaternion" "', argument " "1"" of type '" "iDynTree::Vector4 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_zero" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); } - arg1 = reinterpret_cast< iDynTree::Vector4 * >(argp1); - result = iDynTree::Rotation::RotationFromQuaternion((iDynTree::VectorFixSize< 4 > const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35773,26 +33512,23 @@ int _wrap_Rotation_RotationFromQuaternion(int resc, mxArray *resv[], int argc, m } -int _wrap_Rotation_leftJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AngularMotionVector3 *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_asMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Rotation_leftJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_asMatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_leftJacobian" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_leftJacobian" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_asMatrix" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp1); - result = iDynTree::Rotation::leftJacobian((iDynTree::GeomVector3 const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = ((iDynTree::SpatialInertia const *)arg1)->asMatrix(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35800,50 +33536,34 @@ int _wrap_Rotation_leftJacobian(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Rotation_leftJacobianInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AngularMotionVector3 *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_applyInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 result; + iDynTree::Twist result; - if (!SWIG_check_num_args("Rotation_leftJacobianInverse",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_applyInverse",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_leftJacobianInverse" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_leftJacobianInverse" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_applyInverse" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp1); - result = iDynTree::Rotation::leftJacobianInverse((iDynTree::GeomVector3 const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Rotation_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Rotation_toString",argc,1,1,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_toString" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->applyInverse((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35851,23 +33571,23 @@ int _wrap_Rotation_toString(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Rotation_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_SpatialInertia_getInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Rotation_display",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_getInverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_display" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_getInverse" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - result = ((iDynTree::Rotation const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = ((iDynTree::SpatialInertia const *)arg1)->getInverse(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35875,43 +33595,34 @@ int _wrap_Rotation_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_delete_Rotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; +int _wrap_SpatialInertia_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::SpatialInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::SpatialInertia result; - int is_owned; - if (!SWIG_check_num_args("delete_Rotation",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_plus",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_plus" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_plus" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_Transform__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::Transform *result = 0 ; - - if (!SWIG_check_num_args("new_Transform",argc,0,0,0)) { - SWIG_fail; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_plus" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } - (void)argv; - result = (iDynTree::Transform *)new iDynTree::Transform(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->operator +((iDynTree::SpatialInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35919,37 +33630,34 @@ int _wrap_new_Transform__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Transform__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Rotation *arg1 = 0 ; - iDynTree::Position *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("new_Transform",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Transform" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Rotation const &)*arg1,(iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35957,26 +33665,34 @@ int _wrap_new_Transform__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Transform__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Matrix4x4 *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::Twist *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("new_Transform",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Matrix4x4 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Matrix4x4 const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } - arg1 = reinterpret_cast< iDynTree::Matrix4x4 * >(argp1); - result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Matrix4x4 const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -35984,26 +33700,34 @@ int _wrap_new_Transform__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Transform__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::Wrench result; - if (!SWIG_check_num_args("new_Transform",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_mtimes" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Transform const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36011,80 +33735,87 @@ int _wrap_new_Transform__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_new_Transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Transform__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_SpatialInertia_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Transform__SWIG_2(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SpatialInertia_mtimes__SWIG_1(resc,resv,argc,argv); + } } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Transform__SWIG_3(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SpatialInertia_mtimes__SWIG_2(resc,resv,argc,argv); + } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_Transform__SWIG_1(resc,resv,argc,argv); + return _wrap_SpatialInertia_mtimes__SWIG_0(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Transform'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SpatialInertia_mtimes'." " Possible C/C++ prototypes are:\n" - " iDynTree::Transform::Transform()\n" - " iDynTree::Transform::Transform(iDynTree::Rotation const &,iDynTree::Position const &)\n" - " iDynTree::Transform::Transform(iDynTree::Matrix4x4 const &)\n" - " iDynTree::Transform::Transform(iDynTree::Transform const &)\n"); + " iDynTree::SpatialInertia::operator *(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::SpatialInertia::operator *(iDynTree::Twist const &) const\n" + " iDynTree::SpatialInertia::operator *(iDynTree::SpatialAcc const &) const\n"); return 1; } -int _wrap_Transform_fromHomogeneousTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Matrix4x4 *arg2 = 0 ; +int _wrap_SpatialInertia_biasWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Wrench result; - if (!SWIG_check_num_args("Transform_fromHomogeneousTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_biasWrench",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_fromHomogeneousTransform" "', argument " "1"" of type '" "iDynTree::Transform *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_biasWrench" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_fromHomogeneousTransform" "', argument " "2"" of type '" "iDynTree::Matrix4x4 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_biasWrench" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_fromHomogeneousTransform" "', argument " "2"" of type '" "iDynTree::Matrix4x4 const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_biasWrench" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); } - arg2 = reinterpret_cast< iDynTree::Matrix4x4 * >(argp2); - (arg1)->fromHomogeneousTransform((iDynTree::Matrix4x4 const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->biasWrench((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36092,23 +33823,34 @@ int _wrap_Transform_fromHomogeneousTransform(int resc, mxArray *resv[], int argc } -int _wrap_Transform_getRotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_SpatialInertia_biasWrenchDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Rotation *result = 0 ; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Transform_getRotation",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_biasWrenchDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_getRotation" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = (iDynTree::Rotation *) &((iDynTree::Transform const *)arg1)->getRotation(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_biasWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::SpatialInertia const *)arg1)->biasWrenchDerivative((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36116,23 +33858,16 @@ int _wrap_Transform_getRotation(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Transform_getPosition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_SpatialInertia_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::SpatialInertia result; - if (!SWIG_check_num_args("Transform_getPosition",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_Zero",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_getPosition" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = (iDynTree::Position *) &((iDynTree::Transform const *)arg1)->getPosition(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + (void)argv; + result = iDynTree::SpatialInertia::Zero(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36140,33 +33875,23 @@ int _wrap_Transform_getPosition(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Transform_setRotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Rotation *arg2 = 0 ; +int _wrap_SpatialInertia_asVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; + iDynTree::Vector10 result; - if (!SWIG_check_num_args("Transform_setRotation",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_asVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_setRotation" "', argument " "1"" of type '" "iDynTree::Transform *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_setRotation" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_setRotation" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_asVector" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); - (arg1)->setRotation((iDynTree::Rotation const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = ((iDynTree::SpatialInertia const *)arg1)->asVector(); + _out = SWIG_NewPointerObj((new iDynTree::Vector10(static_cast< const iDynTree::Vector10& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36174,32 +33899,32 @@ int _wrap_Transform_setRotation(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Transform_setPosition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_SpatialInertia_fromVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + iDynTree::Vector10 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Transform_setPosition",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_fromVector",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_setPosition" "', argument " "1"" of type '" "iDynTree::Transform *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_fromVector" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_setPosition" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_fromVector" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_setPosition" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_fromVector" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - (arg1)->setPosition((iDynTree::Position const &)*arg2); + arg2 = reinterpret_cast< iDynTree::Vector10 * >(argp2); + (arg1)->fromVector((iDynTree::Vector10 const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -36208,37 +33933,23 @@ int _wrap_Transform_setPosition(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Transform_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = 0 ; - iDynTree::Transform *arg2 = 0 ; - void *argp1 ; +int _wrap_SpatialInertia_isPhysicallyConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; + bool result; - if (!SWIG_check_num_args("Transform_compose",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_isPhysicallyConsistent",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_compose" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_compose" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_compose" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_compose" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_isPhysicallyConsistent" "', argument " "1"" of type '" "iDynTree::SpatialInertia const *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = iDynTree::Transform::compose((iDynTree::Transform const &)*arg1,(iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = (bool)((iDynTree::SpatialInertia const *)arg1)->isPhysicallyConsistent(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36246,26 +33957,26 @@ int _wrap_Transform_compose(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Transform_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = 0 ; +int _wrap_SpatialInertia_momentumRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::Matrix6x10 result; - if (!SWIG_check_num_args("Transform_inverse2",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_momentumRegressor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_inverse2" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_inverse2" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = iDynTree::Transform::inverse2((iDynTree::Transform const &)*arg1); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + result = iDynTree::SpatialInertia::momentumRegressor((iDynTree::Twist const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36273,34 +33984,37 @@ int _wrap_Transform_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Transform_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Transform *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_SpatialInertia_momentumDerivativeRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::Matrix6x10 result; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("SpatialInertia_momentumDerivativeRegressor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeRegressor" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = iDynTree::SpatialInertia::momentumDerivativeRegressor((iDynTree::Twist const &)*arg1,(iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36308,23 +34022,48 @@ int _wrap_Transform_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - void *argp1 = 0 ; +int _wrap_SpatialInertia_momentumDerivativeSlotineLiRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Twist *arg1 = 0 ; + iDynTree::Twist *arg2 = 0 ; + iDynTree::SpatialAcc *arg3 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::Matrix6x10 result; - if (!SWIG_check_num_args("Transform_inverse",argc,1,1,0)) { + if (!SWIG_check_num_args("SpatialInertia_momentumDerivativeSlotineLiRegressor",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Twist, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_inverse" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->inverse(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "1"" of type '" "iDynTree::Twist const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Twist * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "3"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SpatialInertia_momentumDerivativeSlotineLiRegressor" "', argument " "3"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg3 = reinterpret_cast< iDynTree::SpatialAcc * >(argp3); + result = iDynTree::SpatialInertia::momentumDerivativeSlotineLiRegressor((iDynTree::Twist const &)*arg1,(iDynTree::Twist const &)*arg2,(iDynTree::SpatialAcc const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x10(static_cast< const iDynTree::Matrix6x10& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_10_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36332,34 +34071,26 @@ int _wrap_Transform_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Transform_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Position *arg2 = 0 ; +int _wrap_delete_SpatialInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = (iDynTree::SpatialInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Position result; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SpatialInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SpatialInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Position * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Position const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36367,34 +34098,16 @@ int _wrap_Transform_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Wrench *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_ArticulatedBodyInertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::Wrench result; + iDynTree::ArticulatedBodyInertia *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + (void)argv; + result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36402,34 +34115,39 @@ int _wrap_Transform_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_new_ArticulatedBodyInertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + unsigned int arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + unsigned int val2 ; + int ecode2 = 0 ; + unsigned int val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Twist result; + iDynTree::ArticulatedBodyInertia *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "double const *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_ArticulatedBodyInertia" "', argument " "2"" of type '" "unsigned int""'"); + } + arg2 = static_cast< unsigned int >(val2); + ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_ArticulatedBodyInertia" "', argument " "3"" of type '" "unsigned int""'"); + } + arg3 = static_cast< unsigned int >(val3); + result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36437,34 +34155,26 @@ int _wrap_Transform_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::SpatialMomentum *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_ArticulatedBodyInertia__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialInertia *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMomentum result; + iDynTree::ArticulatedBodyInertia *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::SpatialInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::SpatialInertia * >(argp1); + result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((iDynTree::SpatialInertia const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36472,34 +34182,26 @@ int _wrap_Transform_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_ArticulatedBodyInertia__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc result; + iDynTree::ArticulatedBodyInertia *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::ArticulatedBodyInertia *)new iDynTree::ArticulatedBodyInertia((iDynTree::ArticulatedBodyInertia const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36507,69 +34209,77 @@ int _wrap_Transform_mtimes__SWIG_5(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::SpatialMotionVector *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::SpatialMotionVector result; - - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { - SWIG_fail; +int _wrap_new_ArticulatedBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_ArticulatedBodyInertia__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ArticulatedBodyInertia__SWIG_2(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ArticulatedBodyInertia__SWIG_3(resc,resv,argc,argv); + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_ArticulatedBodyInertia__SWIG_1(resc,resv,argc,argv); + } + } + } } - arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ArticulatedBodyInertia'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia()\n" + " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(double const *,unsigned int const,unsigned int const)\n" + " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(iDynTree::SpatialInertia const &)\n" + " iDynTree::ArticulatedBodyInertia::ArticulatedBodyInertia(iDynTree::ArticulatedBodyInertia const &)\n"); return 1; } -int _wrap_Transform_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::SpatialForceVector *arg2 = 0 ; +int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; + iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearLinearSubmatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearLinearSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &(arg1)->getLinearLinearSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36577,34 +34287,23 @@ int _wrap_Transform_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::SpatialInertia *arg2 = 0 ; +int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia result; + iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearAngularSubmatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &(arg1)->getLinearAngularSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36612,34 +34311,23 @@ int _wrap_Transform_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::ArticulatedBodyInertia *arg2 = 0 ; +int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_getAngularAngularSubmatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getAngularAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); } - arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::ArticulatedBodyInertia const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &(arg1)->getAngularAngularSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36647,34 +34335,23 @@ int _wrap_Transform_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Direction *arg2 = 0 ; +int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Direction result; + iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearLinearSubmatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearLinearSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Direction const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getLinearLinearSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36682,239 +34359,169 @@ int _wrap_Transform_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Transform_mtimes__SWIG_11(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - iDynTree::Axis *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - iDynTree::Axis result; - - if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); - result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Axis const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Transform_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { +int _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_2(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_3(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix__SWIG_1(resc,resv,argc,argv); } } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_4(resc,resv,argc,argv); - } - } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getLinearLinearSubmatrix'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ArticulatedBodyInertia::getLinearLinearSubmatrix()\n" + " iDynTree::ArticulatedBodyInertia::getLinearLinearSubmatrix() const\n"); + return 1; +} + + +int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Matrix3x3 *result = 0 ; + + if (!SWIG_check_num_args("ArticulatedBodyInertia_getLinearAngularSubmatrix",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_5(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getLinearAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - if (argc == 2) { + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getLinearAngularSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_6(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_7(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix__SWIG_1(resc,resv,argc,argv); } } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_8(resc,resv,argc,argv); - } - } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getLinearAngularSubmatrix'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ArticulatedBodyInertia::getLinearAngularSubmatrix()\n" + " iDynTree::ArticulatedBodyInertia::getLinearAngularSubmatrix() const\n"); + return 1; +} + + +int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Matrix3x3 *result = 0 ; + + if (!SWIG_check_num_args("ArticulatedBodyInertia_getAngularAngularSubmatrix",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_9(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getAngularAngularSubmatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - if (argc == 2) { + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = (iDynTree::Matrix3x3 *) &((iDynTree::ArticulatedBodyInertia const *)arg1)->getAngularAngularSubmatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_10(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Transform_mtimes__SWIG_11(resc,resv,argc,argv); - } + return _wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Transform_mtimes'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_getAngularAngularSubmatrix'." " Possible C/C++ prototypes are:\n" - " iDynTree::Transform::operator *(iDynTree::Transform const &) const\n" - " iDynTree::Transform::operator *(iDynTree::Position const &) const\n" - " iDynTree::Transform::operator *(iDynTree::Wrench const &) const\n" - " iDynTree::Transform::operator *(iDynTree::Twist const &) const\n" - " iDynTree::Transform::operator *(iDynTree::SpatialMomentum const &) const\n" - " iDynTree::Transform::operator *(iDynTree::SpatialAcc const &) const\n" - " iDynTree::Transform::operator *(iDynTree::SpatialMotionVector const &) const\n" - " iDynTree::Transform::operator *(iDynTree::SpatialForceVector const &) const\n" - " iDynTree::Transform::operator *(iDynTree::SpatialInertia const &) const\n" - " iDynTree::Transform::operator *(iDynTree::ArticulatedBodyInertia const &) const\n" - " iDynTree::Transform::operator *(iDynTree::Direction const &) const\n" - " iDynTree::Transform::operator *(iDynTree::Axis const &) const\n"); + " iDynTree::ArticulatedBodyInertia::getAngularAngularSubmatrix()\n" + " iDynTree::ArticulatedBodyInertia::getAngularAngularSubmatrix() const\n"); return 1; } -int _wrap_Transform_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ArticulatedBodyInertia_combine(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = 0 ; + iDynTree::ArticulatedBodyInertia *arg2 = 0 ; + void *argp1 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("Transform_Identity",argc,0,0,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_combine",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::Transform::Identity(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_combine" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_combine" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_combine" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_combine" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); + result = iDynTree::ArticulatedBodyInertia::combine((iDynTree::ArticulatedBodyInertia const &)*arg1,(iDynTree::ArticulatedBodyInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36922,23 +34529,34 @@ int _wrap_Transform_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Transform_asHomogeneousTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_applyInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix4x4 result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("Transform_asHomogeneousTransform",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_applyInverse",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asHomogeneousTransform" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->asHomogeneousTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix4x4(static_cast< const iDynTree::Matrix4x4& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_applyInverse" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->applyInverse((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -36946,22 +34564,22 @@ int _wrap_Transform_asHomogeneousTransform(int resc, mxArray *resv[], int argc, } -int _wrap_Transform_asAdjointTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_asMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Transform_asAdjointTransform",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_asMatrix",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asAdjointTransform" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_asMatrix" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->asAdjointTransform(); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->asMatrix(); _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -36970,22 +34588,22 @@ int _wrap_Transform_asAdjointTransform(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_Transform_asAdjointTransformWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_getInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Transform_asAdjointTransformWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_getInverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asAdjointTransformWrench" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_getInverse" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->asAdjointTransformWrench(); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->getInverse(); _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; @@ -36994,47 +34612,34 @@ int _wrap_Transform_asAdjointTransformWrench(int resc, mxArray *resv[], int argc } -int _wrap_Transform_log(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_plus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + iDynTree::ArticulatedBodyInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("Transform_log",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_plus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_log" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_plus" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->log(); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Transform_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("Transform_toString",argc,1,1,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_plus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_toString" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_plus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator +((iDynTree::ArticulatedBodyInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37042,23 +34647,34 @@ int _wrap_Transform_toString(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Transform_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_minus(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + iDynTree::ArticulatedBodyInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::string result; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("Transform_display",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_minus",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_display" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_minus" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = ((iDynTree::Transform const *)arg1)->reservedToString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_minus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_minus" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); + } + arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator -((iDynTree::ArticulatedBodyInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37066,43 +34682,34 @@ int _wrap_Transform_display(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_Transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; +int _wrap_ArticulatedBodyInertia_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::SpatialForceVector result; - int is_owned; - if (!SWIG_check_num_args("delete_Transform",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_mtimes",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Transform" "', argument " "1"" of type '" "iDynTree::Transform *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_TransformDerivative__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::TransformDerivative *result = 0 ; - - if (!SWIG_check_num_args("new_TransformDerivative",argc,0,0,0)) { - SWIG_fail; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - (void)argv; - result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37110,37 +34717,34 @@ int _wrap_new_TransformDerivative__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_new_TransformDerivative__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Matrix3x3 *arg1 = 0 ; - iDynTree::Vector3 *arg2 = 0 ; - void *argp1 ; +int _wrap_ArticulatedBodyInertia_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::TransformDerivative *result = 0 ; + iDynTree::Wrench result; - if (!SWIG_check_num_args("new_TransformDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::Matrix3x3 const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::Matrix3x3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia const *""'"); } - arg1 = reinterpret_cast< iDynTree::Matrix3x3 * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_TransformDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); - result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative((iDynTree::Matrix3x3 const &)*arg1,(iDynTree::Vector3 const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::ArticulatedBodyInertia const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37148,89 +34752,59 @@ int _wrap_new_TransformDerivative__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_TransformDerivative__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::TransformDerivative *result = 0 ; - - if (!SWIG_check_num_args("new_TransformDerivative",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__TransformDerivative, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const &""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative((iDynTree::TransformDerivative const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_TransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_TransformDerivative__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_ArticulatedBodyInertia_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_TransformDerivative__SWIG_2(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ArticulatedBodyInertia_mtimes__SWIG_1(resc,resv,argc,argv); + } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_TransformDerivative__SWIG_1(resc,resv,argc,argv); + return _wrap_ArticulatedBodyInertia_mtimes__SWIG_0(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_TransformDerivative'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ArticulatedBodyInertia_mtimes'." " Possible C/C++ prototypes are:\n" - " iDynTree::TransformDerivative::TransformDerivative()\n" - " iDynTree::TransformDerivative::TransformDerivative(iDynTree::Matrix3x3 const &,iDynTree::Vector3 const &)\n" - " iDynTree::TransformDerivative::TransformDerivative(iDynTree::TransformDerivative const &)\n"); + " iDynTree::ArticulatedBodyInertia::operator *(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::ArticulatedBodyInertia::operator *(iDynTree::SpatialAcc const &) const\n"); return 1; } -int _wrap_delete_TransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; +int _wrap_ArticulatedBodyInertia_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_TransformDerivative",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_zero",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_zero" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); } + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + (arg1)->zero(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -37239,23 +34813,34 @@ int _wrap_delete_TransformDerivative(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_TransformDerivative_getRotationDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - void *argp1 = 0 ; +int _wrap_ArticulatedBodyInertia_ABADyadHelper(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + double arg2 ; + void *argp1 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Matrix3x3 *result = 0 ; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("TransformDerivative_getRotationDerivative",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_ABADyadHelper",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_getRotationDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - result = (iDynTree::Matrix3x3 *) &((iDynTree::TransformDerivative const *)arg1)->getRotationDerivative(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ArticulatedBodyInertia_ABADyadHelper" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = iDynTree::ArticulatedBodyInertia::ABADyadHelper((iDynTree::SpatialForceVector const &)*arg1,arg2); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37263,23 +34848,53 @@ int _wrap_TransformDerivative_getRotationDerivative(int resc, mxArray *resv[], i } -int _wrap_TransformDerivative_getPositionDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - void *argp1 = 0 ; +int _wrap_ArticulatedBodyInertia_ABADyadHelperLin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SpatialForceVector *arg1 = 0 ; + double arg2 ; + iDynTree::SpatialForceVector *arg3 = 0 ; + double arg4 ; + void *argp1 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - iDynTree::Vector3 *result = 0 ; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("TransformDerivative_getPositionDerivative",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyInertia_ABADyadHelperLin",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_getPositionDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - result = (iDynTree::Vector3 *) &((iDynTree::TransformDerivative const *)arg1)->getPositionDerivative(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "1"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "3"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "3"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg3 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "ArticulatedBodyInertia_ABADyadHelperLin" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = iDynTree::ArticulatedBodyInertia::ABADyadHelperLin((iDynTree::SpatialForceVector const &)*arg1,arg2,(iDynTree::SpatialForceVector const &)*arg3,arg4); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37287,32 +34902,25 @@ int _wrap_TransformDerivative_getPositionDerivative(int resc, mxArray *resv[], i } -int _wrap_TransformDerivative_setRotationDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Matrix3x3 *arg2 = 0 ; +int _wrap_delete_ArticulatedBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyInertia *arg1 = (iDynTree::ArticulatedBodyInertia *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("TransformDerivative_setRotationDerivative",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_ArticulatedBodyInertia",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_setRotationDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_setRotationDerivative" "', argument " "2"" of type '" "iDynTree::Matrix3x3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ArticulatedBodyInertia" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyInertia *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_setRotationDerivative" "', argument " "2"" of type '" "iDynTree::Matrix3x3 const &""'"); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Matrix3x3 * >(argp2); - (arg1)->setRotationDerivative((iDynTree::Matrix3x3 const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -37321,32 +34929,29 @@ int _wrap_TransformDerivative_setRotationDerivative(int resc, mxArray *resv[], i } -int _wrap_TransformDerivative_setPositionDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Vector3 *arg2 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_mass_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("TransformDerivative_setPositionDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_mass_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_setPositionDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_setPositionDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_setPositionDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); - (arg1)->setPositionDerivative((iDynTree::Vector3 const &)*arg2); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->mass = arg2; _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -37355,16 +34960,23 @@ int _wrap_TransformDerivative_setPositionDerivative(int resc, mxArray *resv[], i } -int _wrap_TransformDerivative_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_RigidBodyInertiaNonLinearParametrization_mass_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; + double result; - if (!SWIG_check_num_args("TransformDerivative_Zero",argc,0,0,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_mass_get",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::TransformDerivative::Zero(); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_mass_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); + } + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = (double) ((arg1)->mass); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37372,23 +34984,30 @@ int _wrap_TransformDerivative_Zero(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_TransformDerivative_asHomogeneousTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_com_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::Position *arg2 = (iDynTree::Position *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Matrix4x4 result; - if (!SWIG_check_num_args("TransformDerivative_asHomogeneousTransformDerivative",argc,1,1,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_com_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asHomogeneousTransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_com_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - result = ((iDynTree::TransformDerivative const *)arg1)->asHomogeneousTransformDerivative(); - _out = SWIG_NewPointerObj((new iDynTree::Matrix4x4(static_cast< const iDynTree::Matrix4x4& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_com_set" "', argument " "2"" of type '" "iDynTree::Position *""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + if (arg1) (arg1)->com = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37396,34 +35015,23 @@ int _wrap_TransformDerivative_asHomogeneousTransformDerivative(int resc, mxArray } -int _wrap_TransformDerivative_asAdjointTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_com_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("TransformDerivative_asAdjointTransformDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_com_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_com_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = ((iDynTree::TransformDerivative const *)arg1)->asAdjointTransformDerivative((iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = (iDynTree::Position *)& ((arg1)->com); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37431,34 +35039,30 @@ int _wrap_TransformDerivative_asAdjointTransformDerivative(int resc, mxArray *re } -int _wrap_TransformDerivative_asAdjointTransformWrenchDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::Rotation *arg2 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("TransformDerivative_asAdjointTransformWrenchDerivative",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set" "', argument " "2"" of type '" "iDynTree::Rotation *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = ((iDynTree::TransformDerivative const *)arg1)->asAdjointTransformWrenchDerivative((iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + if (arg1) (arg1)->link_R_centroidal = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37466,34 +35070,23 @@ int _wrap_TransformDerivative_asAdjointTransformWrenchDerivative(int resc, mxArr } -int _wrap_TransformDerivative_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("TransformDerivative_mtimes",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_mtimes" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = ((iDynTree::TransformDerivative const *)arg1)->operator *((iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = (iDynTree::Rotation *)& ((arg1)->link_R_centroidal); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37501,34 +35094,30 @@ int _wrap_TransformDerivative_mtimes(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_TransformDerivative_derivativeOfInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::Vector3 *arg2 = (iDynTree::Vector3 *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("TransformDerivative_derivativeOfInverse",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set" "', argument " "2"" of type '" "iDynTree::Vector3 *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = ((iDynTree::TransformDerivative const *)arg1)->derivativeOfInverse((iDynTree::Transform const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); + if (arg1) (arg1)->centralSecondMomentOfMass = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37536,45 +35125,47 @@ int _wrap_TransformDerivative_derivativeOfInverse(int resc, mxArray *resv[], int } -int _wrap_TransformDerivative_transform__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; - iDynTree::ArticulatedBodyInertia *arg3 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia result; + iDynTree::Vector3 *result = 0 ; - if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); - } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::ArticulatedBodyInertia &""'"); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = (iDynTree::Vector3 *)& ((arg1)->centralSecondMomentOfMass); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Transform result; + + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform",argc,1,1,0)) { + SWIG_fail; } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::ArticulatedBodyInertia &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); } - arg3 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp3); - result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); - _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->getLinkCentroidalTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37582,45 +35173,33 @@ int _wrap_TransformDerivative_transform__SWIG_0(int resc, mxArray *resv[], int a } -int _wrap_TransformDerivative_transform__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; - iDynTree::SpatialForceVector *arg3 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::SpatialInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialForceVector &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialForceVector &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } - arg3 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp3); - result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); - _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); + (arg1)->fromRigidBodyInertia((iDynTree::SpatialInertia const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37628,45 +35207,33 @@ int _wrap_TransformDerivative_transform__SWIG_1(int resc, mxArray *resv[], int a } -int _wrap_TransformDerivative_transform__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; - iDynTree::Transform *arg2 = 0 ; - iDynTree::SpatialMotionVector *arg3 = 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_fromInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::Vector10 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromInertialParameters",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_10_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialMotionVector &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialMotionVector &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromInertialParameters" "', argument " "2"" of type '" "iDynTree::Vector10 const &""'"); } - arg3 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp3); - result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Vector10 * >(argp2); + (arg1)->fromInertialParameters((iDynTree::Vector10 const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37674,90 +35241,47 @@ int _wrap_TransformDerivative_transform__SWIG_2(int resc, mxArray *resv[], int a } -int _wrap_TransformDerivative_transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_TransformDerivative_transform__SWIG_0(resc,resv,argc,argv); - } - } - } - } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_TransformDerivative_transform__SWIG_1(resc,resv,argc,argv); - } - } - } +int _wrap_RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia result; + + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia",argc,1,1,0)) { + SWIG_fail; } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_TransformDerivative_transform__SWIG_2(resc,resv,argc,argv); - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'TransformDerivative_transform'." - " Possible C/C++ prototypes are:\n" - " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::ArticulatedBodyInertia &)\n" - " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::SpatialForceVector &)\n" - " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::SpatialMotionVector &)\n"); - return 1; -} - - -SWIGINTERN int _wrap_dynamic_extent_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::dynamic_extent)); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->toRigidBodyInertia(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; return 0; +fail: + return 1; } -int _wrap_DynamicSpan_extent_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::index_type result; + bool result; - if (!SWIG_check_num_args("DynamicSpan_extent_get",argc,0,0,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Span< double,-1 >::index_type)iDynTree::Span< double,-1 >::extent; - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); + } + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = (bool)((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->isPhysicallyConsistent(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37765,31 +35289,23 @@ int _wrap_DynamicSpan_extent_get(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_DynamicSpan__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 >::pointer arg1 = (iDynTree::Span< double,-1 >::pointer) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 > *result = 0 ; + iDynTree::Vector16 result; - if (!SWIG_check_num_args("new_DynamicSpan",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicSpan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->asVectorWithRotationAsVec(); + _out = SWIG_NewPointerObj((new iDynTree::Vector16(static_cast< const iDynTree::Vector16& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37797,31 +35313,33 @@ int _wrap_new_DynamicSpan__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_DynamicSpan__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 >::pointer arg1 = (iDynTree::Span< double,-1 >::pointer) 0 ; - iDynTree::Span< double,-1 >::pointer arg2 = (iDynTree::Span< double,-1 >::pointer) 0 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + iDynTree::Vector16 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 > *result = 0 ; - if (!SWIG_check_num_args("new_DynamicSpan",argc,2,2,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_16_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_DynamicSpan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "2"" of type '" "iDynTree::Vector16 const &""'"); } - arg2 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp2); - result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec" "', argument " "2"" of type '" "iDynTree::Vector16 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Vector16 * >(argp2); + (arg1)->fromVectorWithRotationAsVec((iDynTree::Vector16 const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37829,26 +35347,23 @@ int _wrap_new_DynamicSpan__SWIG_1(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_DynamicSpan__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = 0 ; - void *argp1 ; +int _wrap_RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 > *result = 0 ; + iDynTree::Matrix10x16 result; - if (!SWIG_check_num_args("new_DynamicSpan",argc,1,1,0)) { + if (!SWIG_check_num_args("RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >((iDynTree::Span< double,-1 > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); + result = ((iDynTree::RigidBodyInertiaNonLinearParametrization const *)arg1)->getGradientWithRotationAsVec(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix10x16(static_cast< const iDynTree::Matrix10x16& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_10_16_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37856,71 +35371,39 @@ int _wrap_new_DynamicSpan__SWIG_2(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_DynamicSpan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_DynamicSpan__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_DynamicSpan__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_DynamicSpan__SWIG_0(resc,resv,argc,argv); - } - } - } +int _wrap_new_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::RigidBodyInertiaNonLinearParametrization *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DynamicSpan'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 >::pointer,iDynTree::Span< double,-1 >::index_type)\n" - " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 >::pointer,iDynTree::Span< double,-1 >::pointer)\n" - " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 > const &)\n"); + if (!SWIG_check_num_args("new_RigidBodyInertiaNonLinearParametrization",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::RigidBodyInertiaNonLinearParametrization *)new iDynTree::RigidBodyInertiaNonLinearParametrization(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_delete_DynamicSpan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_delete_RigidBodyInertiaNonLinearParametrization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RigidBodyInertiaNonLinearParametrization *arg1 = (iDynTree::RigidBodyInertiaNonLinearParametrization *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_DynamicSpan",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_RigidBodyInertiaNonLinearParametrization",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RigidBodyInertiaNonLinearParametrization, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_RigidBodyInertiaNonLinearParametrization" "', argument " "1"" of type '" "iDynTree::RigidBodyInertiaNonLinearParametrization *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + arg1 = reinterpret_cast< iDynTree::RigidBodyInertiaNonLinearParametrization * >(argp1); if (is_owned) { delete arg1; } @@ -37932,31 +35415,104 @@ int _wrap_delete_DynamicSpan(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DynamicSpan_first(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; +int _wrap_new_Rotation__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - SwigValueWrapper< iDynTree::Span< double,-1 > > result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_first",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Rotation",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_first" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + (void)argv; + result = (iDynTree::Rotation *)new iDynTree::Rotation(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Rotation__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double arg4 ; + double arg5 ; + double arg6 ; + double arg7 ; + double arg8 ; + double arg9 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; + double val5 ; + int ecode5 = 0 ; + double val6 ; + int ecode6 = 0 ; + double val7 ; + int ecode7 = 0 ; + double val8 ; + int ecode8 = 0 ; + double val9 ; + int ecode9 = 0 ; + mxArray * _out; + iDynTree::Rotation *result = 0 ; + + if (!SWIG_check_num_args("new_Rotation",argc,9,9,0)) { + SWIG_fail; } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_Rotation" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_first" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Rotation" "', argument " "2"" of type '" "double""'"); } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = ((iDynTree::Span< double,-1 > const *)arg1)->first(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Rotation" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "new_Rotation" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + ecode5 = SWIG_AsVal_double(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "new_Rotation" "', argument " "5"" of type '" "double""'"); + } + arg5 = static_cast< double >(val5); + ecode6 = SWIG_AsVal_double(argv[5], &val6); + if (!SWIG_IsOK(ecode6)) { + SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "new_Rotation" "', argument " "6"" of type '" "double""'"); + } + arg6 = static_cast< double >(val6); + ecode7 = SWIG_AsVal_double(argv[6], &val7); + if (!SWIG_IsOK(ecode7)) { + SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "new_Rotation" "', argument " "7"" of type '" "double""'"); + } + arg7 = static_cast< double >(val7); + ecode8 = SWIG_AsVal_double(argv[7], &val8); + if (!SWIG_IsOK(ecode8)) { + SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "new_Rotation" "', argument " "8"" of type '" "double""'"); + } + arg8 = static_cast< double >(val8); + ecode9 = SWIG_AsVal_double(argv[8], &val9); + if (!SWIG_IsOK(ecode9)) { + SWIG_exception_fail(SWIG_ArgError(ecode9), "in method '" "new_Rotation" "', argument " "9"" of type '" "double""'"); + } + arg9 = static_cast< double >(val9); + result = (iDynTree::Rotation *)new iDynTree::Rotation(arg1,arg2,arg3,arg4,arg5,arg6,arg7,arg8,arg9); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37964,31 +35520,26 @@ int _wrap_DynamicSpan_first(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DynamicSpan_last(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; - void *argp1 = 0 ; +int _wrap_new_Rotation__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::Span< double,-1 > > result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_last",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Rotation",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_last" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_last" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = ((iDynTree::Span< double,-1 > const *)arg1)->last(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = (iDynTree::Rotation *)new iDynTree::Rotation((iDynTree::Rotation const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -37996,39 +35547,29 @@ int _wrap_DynamicSpan_last(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DynamicSpan_subspan__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; - iDynTree::Span< double,-1 >::index_type arg3 ; - void *argp1 = 0 ; +int _wrap_new_Rotation__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + SwigValueWrapper< iDynTree::MatrixView< double const > > arg1 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::Span< double,-1 > > result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_subspan",argc,3,3,0)) { + if (!SWIG_check_num_args("new_Rotation",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_subspan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Rotation" "', argument " "1"" of type '" "iDynTree::MatrixView< double const >""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::MatrixView< double const > * >(argp1)); + } } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_subspan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicSpan_subspan" "', argument " "3"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg3 = static_cast< iDynTree::Span< double,-1 >::index_type >(val3); - result = ((iDynTree::Span< double,-1 > const *)arg1)->subspan(arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); + result = (iDynTree::Rotation *)new iDynTree::Rotation(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38036,31 +35577,39 @@ int _wrap_DynamicSpan_subspan__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_DynamicSpan_subspan__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; +int _wrap_new_Rotation__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double *arg1 = (double *) 0 ; + unsigned int arg2 ; + unsigned int arg3 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; + unsigned int val2 ; int ecode2 = 0 ; + unsigned int val3 ; + int ecode3 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::Span< double,-1 > > result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_subspan",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Rotation",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_subspan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Rotation" "', argument " "1"" of type '" "double const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< double * >(argp1); + ecode2 = SWIG_AsVal_unsigned_SS_int(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_subspan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_Rotation" "', argument " "2"" of type '" "unsigned int""'"); } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = ((iDynTree::Span< double,-1 > const *)arg1)->subspan(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); + arg2 = static_cast< unsigned int >(val2); + ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_Rotation" "', argument " "3"" of type '" "unsigned int""'"); + } + arg3 = static_cast< unsigned int >(val3); + result = (iDynTree::Rotation *)new iDynTree::Rotation((double const *)arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38068,93 +35617,147 @@ int _wrap_DynamicSpan_subspan__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_DynamicSpan_subspan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_Rotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Rotation__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_DynamicSpan_subspan__SWIG_1(resc,resv,argc,argv); - } + return _wrap_new_Rotation__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_const_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Rotation__SWIG_3(resc,resv,argc,argv); } } if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + int res = SWIG_AsVal_unsigned_SS_int(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + int res = SWIG_AsVal_unsigned_SS_int(argv[2], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_DynamicSpan_subspan__SWIG_0(resc,resv,argc,argv); + return _wrap_new_Rotation__SWIG_4(resc,resv,argc,argv); } } } } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DynamicSpan_subspan'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Span< double,-1 >::subspan(iDynTree::Span< double,-1 >::index_type,iDynTree::Span< double,-1 >::index_type) const\n" - " iDynTree::Span< double,-1 >::subspan(iDynTree::Span< double,-1 >::index_type) const\n"); - return 1; -} - - -int _wrap_DynamicSpan_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Span< double,-1 >::index_type result; - - if (!SWIG_check_num_args("DynamicSpan_size",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_size" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + if (argc == 9) { + int _v; + { + int res = SWIG_AsVal_double(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[3], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[4], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[5], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[6], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[7], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_double(argv[8], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_Rotation__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + } + } + } + } } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->size(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Rotation'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Rotation::Rotation()\n" + " iDynTree::Rotation::Rotation(double,double,double,double,double,double,double,double,double)\n" + " iDynTree::Rotation::Rotation(iDynTree::Rotation const &)\n" + " iDynTree::Rotation::Rotation(iDynTree::MatrixView< double const >)\n" + " iDynTree::Rotation::Rotation(double const *,unsigned int const,unsigned int const)\n"); return 1; } -int _wrap_DynamicSpan_size_bytes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::index_type result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_size_bytes",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeOrientFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_size_bytes" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeOrientFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->size_bytes(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (iDynTree::Rotation *) &(arg1)->changeOrientFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38162,23 +35765,34 @@ int _wrap_DynamicSpan_size_bytes(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_DynamicSpan_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeRefOrientFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_empty",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeRefOrientFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_empty" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeRefOrientFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = (bool)((iDynTree::Span< double,-1 > const *)arg1)->empty(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeRefOrientFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (iDynTree::Rotation *) &(arg1)->changeRefOrientFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38186,31 +35800,34 @@ int _wrap_DynamicSpan_empty(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DynamicSpan_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; +int _wrap_Rotation_changeCoordinateFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::element_type *result = 0 ; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("DynamicSpan_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordinateFrame",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_brace" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordinateFrame" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_brace" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->operator [](arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordinateFrame" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = (iDynTree::Rotation *) &(arg1)->changeCoordinateFrame((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38218,31 +35835,37 @@ int _wrap_DynamicSpan_brace(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DynamicSpan_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; - void *argp1 = 0 ; +int _wrap_Rotation_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = 0 ; + iDynTree::Rotation *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::element_type *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("DynamicSpan_getVal",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_compose",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_getVal" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_compose" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_getVal" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->getVal(arg2); - _out = SWIG_From_double(static_cast< double >(*result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_compose" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_compose" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_compose" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = iDynTree::Rotation::compose((iDynTree::Rotation const &)*arg1,(iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38250,41 +35873,26 @@ int _wrap_DynamicSpan_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DynamicSpan_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; - iDynTree::Span< double,-1 >::element_type *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_Rotation_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - double temp3 ; - double val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + iDynTree::Rotation result; - if (!SWIG_check_num_args("DynamicSpan_setVal",argc,3,3,0)) { + if (!SWIG_check_num_args("Rotation_inverse2",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_setVal" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_inverse2" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_setVal" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicSpan_setVal" "', argument " "3"" of type '" "double""'"); - } - temp3 = static_cast< double >(val3); - arg3 = &temp3; - result = (bool)(arg1)->setVal(arg2,(iDynTree::Span< double,-1 >::element_type const &)*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_inverse2" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = iDynTree::Rotation::inverse2((iDynTree::Rotation const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38292,31 +35900,34 @@ int _wrap_DynamicSpan_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DynamicSpan_at(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::element_type *result = 0 ; + iDynTree::Position result; - if (!SWIG_check_num_args("DynamicSpan_at",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_at" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_at" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->at(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38324,31 +35935,34 @@ int _wrap_DynamicSpan_at(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DynamicSpan_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; - iDynTree::Span< double,-1 >::index_type arg2 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::element_type *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("DynamicSpan_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_paren" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_paren" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); - } - arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); - result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38356,23 +35970,34 @@ int _wrap_DynamicSpan_paren(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DynamicSpan_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,false > > result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("DynamicSpan_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_begin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->begin(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::iterator(static_cast< const iDynTree::Span< double,-1 >::iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38380,23 +36005,34 @@ int _wrap_DynamicSpan_begin(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DynamicSpan_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,false > > result; + iDynTree::Twist result; - if (!SWIG_check_num_args("DynamicSpan_end",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_end" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->end(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::iterator(static_cast< const iDynTree::Span< double,-1 >::iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38404,23 +36040,34 @@ int _wrap_DynamicSpan_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DynamicSpan_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,true > > result; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("DynamicSpan_cbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_cbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->cbegin(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_iterator(static_cast< const iDynTree::Span< double,-1 >::const_iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38428,23 +36075,34 @@ int _wrap_DynamicSpan_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DynamicSpan_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,true > > result; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("DynamicSpan_cend",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_cend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->cend(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_iterator(static_cast< const iDynTree::Span< double,-1 >::const_iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38452,23 +36110,34 @@ int _wrap_DynamicSpan_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DynamicSpan_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::reverse_iterator result; + iDynTree::Wrench result; - if (!SWIG_check_num_args("DynamicSpan_rbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_rbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->rbegin(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38476,23 +36145,34 @@ int _wrap_DynamicSpan_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DynamicSpan_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Direction *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::reverse_iterator result; + iDynTree::Direction result; - if (!SWIG_check_num_args("DynamicSpan_rend",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_rend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->rend(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Direction const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38500,23 +36180,34 @@ int _wrap_DynamicSpan_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DynamicSpan_crbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Axis *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::const_reverse_iterator result; + iDynTree::Axis result; - if (!SWIG_check_num_args("DynamicSpan_crbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_crbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->crbegin(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::const_reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::Axis const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38524,40 +36215,34 @@ int _wrap_DynamicSpan_crbegin(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_DynamicSpan_crend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::ClassicalAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Span< double,-1 >::const_reverse_iterator result; + iDynTree::ClassicalAcc result; - if (!SWIG_check_num_args("DynamicSpan_crend",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_crend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); - result = ((iDynTree::Span< double,-1 > const *)arg1)->crend(); - _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::const_reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_DynamicMatrixView__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::MatrixView< double > *result = 0 ; - - if (!SWIG_check_num_args("new_DynamicMatrixView",argc,0,0,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); } - (void)argv; - result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::ClassicalAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38565,26 +36250,34 @@ int _wrap_new_DynamicMatrixView__SWIG_0(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_DynamicMatrixView__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = 0 ; - void *argp1 ; +int _wrap_Rotation_changeCoordFrameOf__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::RotationalInertia *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::MatrixView< double > *result = 0 ; + iDynTree::RotationalInertia result; - if (!SWIG_check_num_args("new_DynamicMatrixView",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_changeCoordFrameOf",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_changeCoordFrameOf" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const &""'"); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationalInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertia const &""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >((iDynTree::MatrixView< double > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_changeCoordFrameOf" "', argument " "2"" of type '" "iDynTree::RotationalInertia const &""'"); + } + arg2 = reinterpret_cast< iDynTree::RotationalInertia * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->changeCoordFrameOf((iDynTree::RotationalInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::RotationalInertia(static_cast< const iDynTree::RotationalInertia& >(result))), SWIGTYPE_p_iDynTree__RotationalInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38592,186 +36285,207 @@ int _wrap_new_DynamicMatrixView__SWIG_1(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_DynamicMatrixView__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double >::pointer arg1 = (iDynTree::MatrixView< double >::pointer) 0 ; - iDynTree::MatrixView< double >::index_type arg2 ; - iDynTree::MatrixView< double >::index_type arg3 ; - iDynTree::MatrixStorageOrdering *arg4 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - int val4 ; - int ecode4 ; - iDynTree::MatrixStorageOrdering temp4 ; - mxArray * _out; - iDynTree::MatrixView< double > *result = 0 ; - - if (!SWIG_check_num_args("new_DynamicMatrixView",argc,4,4,0)) { - SWIG_fail; +int _wrap_Rotation_changeCoordFrameOf(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_0(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double >::pointer""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_3(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::MatrixView< double >::pointer >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicMatrixView" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_DynamicMatrixView" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); - ecode4 = SWIG_AsVal_int (argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "new_DynamicMatrixView" "', argument " "4"" of type '" "iDynTree::MatrixStorageOrdering const &""'"); - } else { - temp4 = static_cast< iDynTree::MatrixStorageOrdering >(val4); - arg4 = &temp4; + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_5(resc,resv,argc,argv); + } + } } - result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(arg1,arg2,arg3,(iDynTree::MatrixStorageOrdering const &)*arg4); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_DynamicMatrixView__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double >::pointer arg1 = (iDynTree::MatrixView< double >::pointer) 0 ; - iDynTree::MatrixView< double >::index_type arg2 ; - iDynTree::MatrixView< double >::index_type arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - mxArray * _out; - iDynTree::MatrixView< double > *result = 0 ; - - if (!SWIG_check_num_args("new_DynamicMatrixView",argc,3,3,0)) { - SWIG_fail; + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_4(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double >::pointer""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_1(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::MatrixView< double >::pointer >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicMatrixView" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_DynamicMatrixView" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); - result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_DynamicMatrixView(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_DynamicMatrixView__SWIG_0(resc,resv,argc,argv); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_6(resc,resv,argc,argv); + } + } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_DynamicMatrixView__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_2(resc,resv,argc,argv); + } } } - if (argc == 3) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_7(resc,resv,argc,argv); } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_DynamicMatrixView__SWIG_3(resc,resv,argc,argv); - } + return _wrap_Rotation_changeCoordFrameOf__SWIG_8(resc,resv,argc,argv); } } } - if (argc == 4) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_changeCoordFrameOf__SWIG_9(resc,resv,argc,argv); } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__RotationalInertia, 0); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_int(argv[3], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_DynamicMatrixView__SWIG_2(resc,resv,argc,argv); - } - } + return _wrap_Rotation_changeCoordFrameOf__SWIG_10(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DynamicMatrixView'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_changeCoordFrameOf'." " Possible C/C++ prototypes are:\n" - " iDynTree::MatrixView< double >::MatrixView()\n" - " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double > const &)\n" - " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double >::pointer,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixStorageOrdering const &)\n" - " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double >::pointer,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixView< double >::index_type)\n"); + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Position const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialForceVector const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Twist const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialAcc const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::SpatialMomentum const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Wrench const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Direction const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::Axis const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::ClassicalAcc const &) const\n" + " iDynTree::Rotation::changeCoordFrameOf(iDynTree::RotationalInertia const &) const\n"); return 1; } -int _wrap_DynamicMatrixView_storageOrder(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; +int _wrap_Rotation_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Rotation *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::MatrixStorageOrdering *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("DynamicMatrixView_storageOrder",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_storageOrder" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - result = (iDynTree::MatrixStorageOrdering *) &((iDynTree::MatrixView< double > const *)arg1)->storageOrder(); - _out = SWIG_From_int(static_cast< int >(*result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Rotation const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38779,39 +36493,23 @@ int _wrap_DynamicMatrixView_storageOrder(int resc, mxArray *resv[], int argc, mx } -int _wrap_DynamicMatrixView_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; - iDynTree::MatrixView< double >::index_type arg2 ; - iDynTree::MatrixView< double >::index_type arg3 ; +int _wrap_Rotation_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::MatrixView< double >::element_type *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("DynamicMatrixView_paren",argc,3,3,0)) { + if (!SWIG_check_num_args("Rotation_inverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_paren" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_inverse" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicMatrixView_paren" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicMatrixView_paren" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); - result = (iDynTree::MatrixView< double >::element_type *) &((iDynTree::MatrixView< double > const *)arg1)->operator ()(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->inverse(); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38819,23 +36517,34 @@ int _wrap_DynamicMatrixView_paren(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_DynamicMatrixView_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; +int _wrap_Rotation_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::MatrixView< double >::index_type result; + iDynTree::Position result; - if (!SWIG_check_num_args("DynamicMatrixView_rows",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_rows" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - result = ((iDynTree::MatrixView< double > const *)arg1)->rows(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38843,23 +36552,34 @@ int _wrap_DynamicMatrixView_rows(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_DynamicMatrixView_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; +int _wrap_Rotation_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::MatrixView< double >::index_type result; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("DynamicMatrixView_cols",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_cols" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - result = ((iDynTree::MatrixView< double > const *)arg1)->cols(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38867,55 +36587,34 @@ int _wrap_DynamicMatrixView_cols(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_DynamicMatrixView_block(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; - iDynTree::MatrixView< double >::index_type arg2 ; - iDynTree::MatrixView< double >::index_type arg3 ; - iDynTree::MatrixView< double >::index_type arg4 ; - iDynTree::MatrixView< double >::index_type arg5 ; +int _wrap_Rotation_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - ptrdiff_t val4 ; - int ecode4 = 0 ; - ptrdiff_t val5 ; - int ecode5 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::MatrixView< double > result; + iDynTree::Twist result; - if (!SWIG_check_num_args("DynamicMatrixView_block",argc,5,5,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_block" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicMatrixView_block" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicMatrixView_block" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); - ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "DynamicMatrixView_block" "', argument " "4"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg4 = static_cast< iDynTree::MatrixView< double >::index_type >(val4); - ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "DynamicMatrixView_block" "', argument " "5"" of type '" "iDynTree::MatrixView< double >::index_type""'"); - } - arg5 = static_cast< iDynTree::MatrixView< double >::index_type >(val5); - result = ((iDynTree::MatrixView< double > const *)arg1)->block(arg2,arg3,arg4,arg5); - _out = SWIG_NewPointerObj((new iDynTree::MatrixView< double >(static_cast< const iDynTree::MatrixView< double >& >(result))), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -38923,243 +36622,104 @@ int _wrap_DynamicMatrixView_block(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_delete_DynamicMatrixView(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; +int _wrap_Rotation_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Wrench result; - int is_owned; - if (!SWIG_check_num_args("delete_DynamicMatrixView",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > *""'"); - } - arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_LINK_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::LINK_INVALID_INDEX)); - return 0; -} - - -SWIGINTERN int _wrap_LINK_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - ptrdiff_t val; - int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); - if (!SWIG_IsOK(res)) { - SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::LINK_INVALID_INDEX""' of type '""iDynTree::LinkIndex""'"); - } - iDynTree::LINK_INVALID_INDEX = static_cast< iDynTree::LinkIndex >(val); - } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_LINK_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::LINK_INVALID_NAME)); - return 0; -} - - -SWIGINTERN int _wrap_LINK_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[0], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::LINK_INVALID_NAME""' of type '""std::string""'"); - } - iDynTree::LINK_INVALID_NAME = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_JOINT_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::JOINT_INVALID_INDEX)); - return 0; -} - - -SWIGINTERN int _wrap_JOINT_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - ptrdiff_t val; - int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); - if (!SWIG_IsOK(res)) { - SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::JOINT_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); - } - iDynTree::JOINT_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_JOINT_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::JOINT_INVALID_NAME)); - return 0; -} - - -SWIGINTERN int _wrap_JOINT_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[0], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::JOINT_INVALID_NAME""' of type '""std::string""'"); - } - iDynTree::JOINT_INVALID_NAME = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_DOF_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::DOF_INVALID_INDEX)); - return 0; -} - - -SWIGINTERN int _wrap_DOF_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - ptrdiff_t val; - int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); - if (!SWIG_IsOK(res)) { - SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::DOF_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); - } - iDynTree::DOF_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; return 0; fail: return 1; } -SWIGINTERN int _wrap_DOF_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::DOF_INVALID_NAME)); - return 0; -} - - -SWIGINTERN int _wrap_DOF_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[0], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::DOF_INVALID_NAME""' of type '""std::string""'"); - } - iDynTree::DOF_INVALID_NAME = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; +int _wrap_Rotation_mtimes__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Direction *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + iDynTree::Direction result; + + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { + SWIG_fail; } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_FRAME_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::FRAME_INVALID_INDEX)); - return 0; -} - - -SWIGINTERN int _wrap_FRAME_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - ptrdiff_t val; - int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); - if (!SWIG_IsOK(res)) { - SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::FRAME_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); - } - iDynTree::FRAME_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_FRAME_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::FRAME_INVALID_NAME)); - return 0; -} - - -SWIGINTERN int _wrap_FRAME_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[0], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::FRAME_INVALID_NAME""' of type '""std::string""'"); - } - iDynTree::FRAME_INVALID_NAME = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - return 0; -fail: - return 1; -} - - -SWIGINTERN int _wrap_TRAVERSAL_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::TRAVERSAL_INVALID_INDEX)); - return 0; -} - - -SWIGINTERN int _wrap_TRAVERSAL_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - { - ptrdiff_t val; - int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); - if (!SWIG_IsOK(res)) { - SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::TRAVERSAL_INVALID_INDEX""' of type '""iDynTree::TraversalIndex""'"); - } - iDynTree::TRAVERSAL_INVALID_INDEX = static_cast< iDynTree::TraversalIndex >(val); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Direction const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; return 0; fail: return 1; } -int _wrap_new_LinkPositions__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Rotation_mtimes__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Axis *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkPositions *result = 0 ; + iDynTree::Axis result; - if (!SWIG_check_num_args("new_LinkPositions",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkPositions" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::Axis const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39167,16 +36727,34 @@ int _wrap_new_LinkPositions__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkPositions__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Rotation_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkPositions *result = 0 ; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("new_LinkPositions",argc,0,0,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39184,26 +36762,34 @@ int _wrap_new_LinkPositions__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkPositions__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Rotation_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkPositions *result = 0 ; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("new_LinkPositions",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkPositions" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkPositions" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39211,63 +36797,34 @@ int _wrap_new_LinkPositions__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkPositions__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkPositions__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkPositions__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkPositions'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkPositions::LinkPositions(std::size_t)\n" - " iDynTree::LinkPositions::LinkPositions()\n" - " iDynTree::LinkPositions::LinkPositions(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkPositions_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - std::size_t arg2 ; +int _wrap_Rotation_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::ClassicalAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::ClassicalAcc result; - if (!SWIG_check_num_args("LinkPositions_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_resize" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ClassicalAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::ClassicalAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::ClassicalAcc * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::ClassicalAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ClassicalAcc(static_cast< const iDynTree::ClassicalAcc& >(result))), SWIGTYPE_p_iDynTree__ClassicalAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39275,33 +36832,34 @@ int _wrap_LinkPositions_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_LinkPositions_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Rotation_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::RotationalInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::RotationalInertia result; - if (!SWIG_check_num_args("LinkPositions_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_resize" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_mtimes" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__RotationalInertia, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::RotationalInertia const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_mtimes" "', argument " "2"" of type '" "iDynTree::RotationalInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::RotationalInertia * >(argp2); + result = ((iDynTree::Rotation const *)arg1)->operator *((iDynTree::RotationalInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::RotationalInertia(static_cast< const iDynTree::RotationalInertia& >(result))), SWIGTYPE_p_iDynTree__RotationalInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39309,73 +36867,230 @@ int _wrap_LinkPositions_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_LinkPositions_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Rotation_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkPositions_resize__SWIG_1(resc,resv,argc,argv); + return _wrap_Rotation_mtimes__SWIG_0(resc,resv,argc,argv); } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkPositions_resize__SWIG_0(resc,resv,argc,argv); + return _wrap_Rotation_mtimes__SWIG_1(resc,resv,argc,argv); } } } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkPositions_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkPositions::resize(std::size_t)\n" - " iDynTree::LinkPositions::resize(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkPositions_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("LinkPositions_isConsistent",argc,2,2,0)) { - SWIG_fail; + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_4(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_3(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_8(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_5(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_6(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_7(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_2(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ClassicalAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_9(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__RotationalInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_mtimes__SWIG_10(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_mtimes'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Rotation::operator *(iDynTree::Rotation const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::Position const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::SpatialForceVector const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::Twist const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::Wrench const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::Direction const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::Axis const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::SpatialAcc const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::SpatialMomentum const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::ClassicalAcc const &) const\n" + " iDynTree::Rotation::operator *(iDynTree::RotationalInertia const &) const\n"); + return 1; +} + + +int _wrap_Rotation_log(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::AngularMotionVector3 result; + + if (!SWIG_check_num_args("Rotation_log",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_log" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->log(); + _out = SWIG_NewPointerObj((new iDynTree::AngularMotionVector3(static_cast< const iDynTree::AngularMotionVector3& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Rotation_fromQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Vector4 *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("Rotation_fromQuaternion",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_fromQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_fromQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_fromQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkPositions const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Vector4 * >(argp2); + (arg1)->fromQuaternion((iDynTree::Vector4 const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39383,23 +37098,55 @@ int _wrap_LinkPositions_isConsistent(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkPositions_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; +int _wrap_Rotation_getRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + double *arg2 = 0 ; + double *arg3 = 0 ; + double *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - size_t result; - if (!SWIG_check_num_args("LinkPositions_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_getRPY",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getRPY" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - result = ((iDynTree::LinkPositions const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getRPY" "', argument " "2"" of type '" "double &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "2"" of type '" "double &""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Rotation_getRPY" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Rotation_getRPY" "', argument " "4"" of type '" "double &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getRPY" "', argument " "4"" of type '" "double &""'"); + } + arg4 = reinterpret_cast< double * >(argp4); + ((iDynTree::Rotation const *)arg1)->getRPY(*arg2,*arg3,*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39407,31 +37154,23 @@ int _wrap_LinkPositions_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkPositions_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_Rotation_asRPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::Vector3 result; - if (!SWIG_check_num_args("LinkPositions_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_asRPY",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_paren" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_asRPY" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Transform *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->asRPY(); + _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39439,31 +37178,34 @@ int _wrap_LinkPositions_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkPositions_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_Rotation_getQuaternion__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + iDynTree::Vector4 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + bool result; - if (!SWIG_check_num_args("LinkPositions_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_getQuaternion",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_paren" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Transform *) &((iDynTree::LinkPositions const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "iDynTree::Vector4 &""'"); + } + arg2 = reinterpret_cast< iDynTree::Vector4 * >(argp2); + result = (bool)((iDynTree::Rotation const *)arg1)->getQuaternion(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39471,74 +37213,144 @@ int _wrap_LinkPositions_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkPositions_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Rotation_getQuaternion__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + double *arg2 = 0 ; + double *arg3 = 0 ; + double *arg4 = 0 ; + double *arg5 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("Rotation_getQuaternion",argc,5,5,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_getQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "double &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "2"" of type '" "double &""'"); + } + arg2 = reinterpret_cast< double * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Rotation_getQuaternion" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Rotation_getQuaternion" "', argument " "4"" of type '" "double &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "4"" of type '" "double &""'"); + } + arg4 = reinterpret_cast< double * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Rotation_getQuaternion" "', argument " "5"" of type '" "double &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_getQuaternion" "', argument " "5"" of type '" "double &""'"); + } + arg5 = reinterpret_cast< double * >(argp5); + result = (bool)((iDynTree::Rotation const *)arg1)->getQuaternion(*arg2,*arg3,*arg4,*arg5); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Rotation_getQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkPositions_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_Rotation_getQuaternion__SWIG_0(resc,resv,argc,argv); } } } - if (argc == 2) { + if (argc == 5) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkPositions_paren__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Rotation_getQuaternion__SWIG_1(resc,resv,argc,argv); + } + } + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkPositions_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Rotation_getQuaternion'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkPositions::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkPositions::operator ()(iDynTree::LinkIndex const) const\n"); + " iDynTree::Rotation::getQuaternion(iDynTree::Vector4 &) const\n" + " iDynTree::Rotation::getQuaternion(double &,double &,double &,double &) const\n"); return 1; } -int _wrap_LinkPositions_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Rotation_asQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - std::string result; + iDynTree::Vector4 result; - if (!SWIG_check_num_args("LinkPositions_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_asQuaternion",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_toString" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_asQuaternion" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::LinkPositions const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->asQuaternion(); + _out = SWIG_NewPointerObj((new iDynTree::Vector4(static_cast< const iDynTree::Vector4& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39546,26 +37358,23 @@ int _wrap_LinkPositions_toString(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_delete_LinkPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_Rotation_RotX(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double val1 ; + int ecode1 = 0 ; mxArray * _out; + iDynTree::Rotation result; - int is_owned; - if (!SWIG_check_num_args("delete_LinkPositions",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_RotX",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkPositions" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotX" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + result = iDynTree::Rotation::RotX(arg1); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39573,23 +37382,23 @@ int _wrap_delete_LinkPositions(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_LinkWrenches__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; +int _wrap_Rotation_RotY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double val1 ; int ecode1 = 0 ; mxArray * _out; - iDynTree::LinkWrenches *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("new_LinkWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_RotY",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + ecode1 = SWIG_AsVal_double(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotY" "', argument " "1"" of type '" "double""'"); } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + arg1 = static_cast< double >(val1); + result = iDynTree::Rotation::RotY(arg1); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39597,16 +37406,23 @@ int _wrap_new_LinkWrenches__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkWrenches__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Rotation_RotZ(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::LinkWrenches *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("new_LinkWrenches",argc,0,0,0)) { + if (!SWIG_check_num_args("Rotation_RotZ",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RotZ" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + result = iDynTree::Rotation::RotZ(arg1); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39614,26 +37430,34 @@ int _wrap_new_LinkWrenches__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkWrenches__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; +int _wrap_Rotation_RotAxis(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = 0 ; + double arg2 ; void *argp1 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::LinkWrenches *result = 0 ; + iDynTree::Rotation result; - if (!SWIG_check_num_args("new_LinkWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_RotAxis",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotAxis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotAxis" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RotAxis" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + result = iDynTree::Rotation::RotAxis((iDynTree::Direction const &)*arg1,arg2); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39641,63 +37465,34 @@ int _wrap_new_LinkWrenches__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkWrenches__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkWrenches__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkWrenches__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkWrenches'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkWrenches::LinkWrenches(std::size_t)\n" - " iDynTree::LinkWrenches::LinkWrenches()\n" - " iDynTree::LinkWrenches::LinkWrenches(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkWrenches_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; +int _wrap_Rotation_RotAxisDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Direction *arg1 = 0 ; + double arg2 ; + void *argp1 ; int res1 = 0 ; - size_t val2 ; + double val2 ; int ecode2 = 0 ; mxArray * _out; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("LinkWrenches_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_RotAxisDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Direction, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotAxisDerivative" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotAxisDerivative" "', argument " "1"" of type '" "iDynTree::Direction const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Direction * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RotAxisDerivative" "', argument " "2"" of type '" "double""'"); } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg2 = static_cast< double >(val2); + result = iDynTree::Rotation::RotAxisDerivative((iDynTree::Direction const &)*arg1,arg2); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39705,33 +37500,39 @@ int _wrap_LinkWrenches_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_Rotation_RPY(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; + iDynTree::Rotation result; - if (!SWIG_check_num_args("LinkWrenches_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_RPY",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPY" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPY" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPY" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = iDynTree::Rotation::RPY(arg1,arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39739,73 +37540,39 @@ int _wrap_LinkWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkWrenches_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkWrenches_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkWrenches_resize__SWIG_0(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkWrenches_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkWrenches::resize(std::size_t)\n" - " iDynTree::LinkWrenches::resize(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkWrenches_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_Rotation_RPYRightTrivializedDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - bool result; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("LinkWrenches_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivative",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkWrenches const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivative" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = iDynTree::Rotation::RPYRightTrivializedDerivative(arg1,arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39813,23 +37580,63 @@ int _wrap_LinkWrenches_isConsistent(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_Rotation_RPYRightTrivializedDerivativeRateOfChange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double arg4 ; + double arg5 ; + double arg6 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; + double val5 ; + int ecode5 = 0 ; + double val6 ; + int ecode6 = 0 ; mxArray * _out; - size_t result; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("LinkWrenches_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeRateOfChange",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - result = ((iDynTree::LinkWrenches const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + ecode5 = SWIG_AsVal_double(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "5"" of type '" "double""'"); + } + arg5 = static_cast< double >(val5); + ecode6 = SWIG_AsVal_double(argv[5], &val6); + if (!SWIG_IsOK(ecode6)) { + SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "Rotation_RPYRightTrivializedDerivativeRateOfChange" "', argument " "6"" of type '" "double""'"); + } + arg6 = static_cast< double >(val6); + result = iDynTree::Rotation::RPYRightTrivializedDerivativeRateOfChange(arg1,arg2,arg3,arg4,arg5,arg6); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39837,31 +37644,39 @@ int _wrap_LinkWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkWrenches_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; +int _wrap_Rotation_RPYRightTrivializedDerivativeInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("LinkWrenches_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeInverse",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_paren" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "2"" of type '" "double""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Wrench *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeInverse" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + result = iDynTree::Rotation::RPYRightTrivializedDerivativeInverse(arg1,arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39869,31 +37684,63 @@ int _wrap_LinkWrenches_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkWrenches_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; +int _wrap_Rotation_RPYRightTrivializedDerivativeInverseRateOfChange(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double arg4 ; + double arg5 ; + double arg6 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; + double val5 ; + int ecode5 = 0 ; + double val6 ; + int ecode6 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("LinkWrenches_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_RPYRightTrivializedDerivativeInverseRateOfChange",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_paren" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "2"" of type '" "double""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Wrench *) &((iDynTree::LinkWrenches const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + ecode5 = SWIG_AsVal_double(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "5"" of type '" "double""'"); + } + arg5 = static_cast< double >(val5); + ecode6 = SWIG_AsVal_double(argv[5], &val6); + if (!SWIG_IsOK(ecode6)) { + SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange" "', argument " "6"" of type '" "double""'"); + } + arg6 = static_cast< double >(val6); + result = iDynTree::Rotation::RPYRightTrivializedDerivativeInverseRateOfChange(arg1,arg2,arg3,arg4,arg5,arg6); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39901,74 +37748,59 @@ int _wrap_LinkWrenches_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkWrenches_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkWrenches_paren__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_Rotation_QuaternionRightTrivializedDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Vector4 arg1 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + SwigValueWrapper< iDynTree::MatrixFixSize< 4,3 > > result; + + if (!SWIG_check_num_args("Rotation_QuaternionRightTrivializedDerivative",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkWrenches_paren__SWIG_1(resc,resv,argc,argv); - } + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_QuaternionRightTrivializedDerivative" "', argument " "1"" of type '" "iDynTree::Vector4""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_QuaternionRightTrivializedDerivative" "', argument " "1"" of type '" "iDynTree::Vector4""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Vector4 * >(argp1)); } } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkWrenches_paren'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkWrenches::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkWrenches::operator ()(iDynTree::LinkIndex const) const\n"); + result = iDynTree::Rotation::QuaternionRightTrivializedDerivative(arg1); + _out = SWIG_NewPointerObj((new iDynTree::MatrixFixSize< 4,3 >(static_cast< const iDynTree::MatrixFixSize< 4,3 >& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_3_t, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinkWrenches_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_Rotation_QuaternionRightTrivializedDerivativeInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Vector4 arg1 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - std::string result; + SwigValueWrapper< iDynTree::MatrixFixSize< 3,4 > > result; - if (!SWIG_check_num_args("LinkWrenches_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_QuaternionRightTrivializedDerivativeInverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_toString" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + { + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_QuaternionRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "iDynTree::Vector4""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_QuaternionRightTrivializedDerivativeInverse" "', argument " "1"" of type '" "iDynTree::Vector4""'"); + } else { + arg1 = *(reinterpret_cast< iDynTree::Vector4 * >(argp1)); + } } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::LinkWrenches const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + result = iDynTree::Rotation::QuaternionRightTrivializedDerivativeInverse(arg1); + _out = SWIG_NewPointerObj((new iDynTree::MatrixFixSize< 3,4 >(static_cast< const iDynTree::MatrixFixSize< 3,4 >& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_4_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39976,22 +37808,16 @@ int _wrap_LinkWrenches_toString(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_LinkWrenches_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_Rotation_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::Rotation result; - if (!SWIG_check_num_args("LinkWrenches_zero",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_Identity",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_zero" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - (arg1)->zero(); - _out = (mxArray*)0; + (void)argv; + result = iDynTree::Rotation::Identity(); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -39999,26 +37825,26 @@ int _wrap_LinkWrenches_zero(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_LinkWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_Rotation_RotationFromQuaternion(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Vector4 *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; + iDynTree::Rotation result; - int is_owned; - if (!SWIG_check_num_args("delete_LinkWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_RotationFromQuaternion",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorFixSizeT_4_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkWrenches" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_RotationFromQuaternion" "', argument " "1"" of type '" "iDynTree::Vector4 const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_RotationFromQuaternion" "', argument " "1"" of type '" "iDynTree::Vector4 const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Vector4 * >(argp1); + result = iDynTree::Rotation::RotationFromQuaternion((iDynTree::VectorFixSize< 4 > const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Rotation(static_cast< const iDynTree::Rotation& >(result))), SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40026,23 +37852,26 @@ int _wrap_delete_LinkWrenches(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_LinkInertias__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Rotation_leftJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AngularMotionVector3 *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkInertias *result = 0 ; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("new_LinkInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_leftJacobian",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkInertias" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_leftJacobian" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_leftJacobian" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + arg1 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp1); + result = iDynTree::Rotation::leftJacobian((iDynTree::GeomVector3 const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40050,16 +37879,26 @@ int _wrap_new_LinkInertias__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkInertias__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Rotation_leftJacobianInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AngularMotionVector3 *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkInertias *result = 0 ; + iDynTree::Matrix3x3 result; - if (!SWIG_check_num_args("new_LinkInertias",argc,0,0,0)) { + if (!SWIG_check_num_args("Rotation_leftJacobianInverse",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_leftJacobianInverse" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Rotation_leftJacobianInverse" "', argument " "1"" of type '" "iDynTree::AngularMotionVector3 const &""'"); + } + arg1 = reinterpret_cast< iDynTree::AngularMotionVector3 * >(argp1); + result = iDynTree::Rotation::leftJacobianInverse((iDynTree::GeomVector3 const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Matrix3x3(static_cast< const iDynTree::Matrix3x3& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40067,26 +37906,23 @@ int _wrap_new_LinkInertias__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkInertias__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Rotation_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkInertias *result = 0 ; + std::string result; - if (!SWIG_check_num_args("new_LinkInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Rotation_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_toString" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40094,63 +37930,23 @@ int _wrap_new_LinkInertias__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkInertias__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkInertias__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkInertias__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkInertias'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkInertias::LinkInertias(std::size_t)\n" - " iDynTree::LinkInertias::LinkInertias()\n" - " iDynTree::LinkInertias::LinkInertias(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkInertias_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; - std::size_t arg2 ; +int _wrap_Rotation_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("LinkInertias_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Rotation_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Rotation_display" "', argument " "1"" of type '" "iDynTree::Rotation const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + result = ((iDynTree::Rotation const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40158,32 +37954,25 @@ int _wrap_LinkInertias_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkInertias_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_delete_Rotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = (iDynTree::Rotation *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("LinkInertias_resize",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Rotation",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Rotation, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Rotation" "', argument " "1"" of type '" "iDynTree::Rotation *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -40192,73 +37981,54 @@ int _wrap_LinkInertias_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkInertias_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkInertias_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkInertias_resize__SWIG_0(resc,resv,argc,argv); - } - } - } +int _wrap_new_Transform__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::Transform *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkInertias_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkInertias::resize(std::size_t)\n" - " iDynTree::LinkInertias::resize(iDynTree::Model const &)\n"); + if (!SWIG_check_num_args("new_Transform",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::Transform *)new iDynTree::Transform(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinkInertias_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_new_Transform__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Rotation *arg1 = 0 ; + iDynTree::Position *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("LinkInertias_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Transform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Rotation, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkInertias const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Rotation const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Rotation * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_Transform" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkInertias const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Rotation const &)*arg1,(iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40266,31 +38036,26 @@ int _wrap_LinkInertias_isConsistent(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkInertias_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; +int _wrap_new_Transform__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Matrix4x4 *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("LinkInertias_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Transform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Matrix4x4 const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::SpatialInertia *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Matrix4x4 const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Matrix4x4 * >(argp1); + result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Matrix4x4 const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40298,31 +38063,26 @@ int _wrap_LinkInertias_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkInertias_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; +int _wrap_new_Transform__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("LinkInertias_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Transform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkInertias const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::SpatialInertia *) &((iDynTree::LinkInertias const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Transform" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = (iDynTree::Transform *)new iDynTree::Transform((iDynTree::Transform const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40330,65 +38090,79 @@ int _wrap_LinkInertias_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkInertias_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_Transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Transform__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkInertias_paren__SWIG_0(resc,resv,argc,argv); - } + return _wrap_new_Transform__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_Transform__SWIG_3(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Rotation, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkInertias_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_new_Transform__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkInertias_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Transform'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkInertias::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkInertias::operator ()(iDynTree::LinkIndex const) const\n"); + " iDynTree::Transform::Transform()\n" + " iDynTree::Transform::Transform(iDynTree::Rotation const &,iDynTree::Position const &)\n" + " iDynTree::Transform::Transform(iDynTree::Matrix4x4 const &)\n" + " iDynTree::Transform::Transform(iDynTree::Transform const &)\n"); return 1; } -int _wrap_delete_LinkInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; +int _wrap_Transform_fromHomogeneousTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Matrix4x4 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_LinkInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_fromHomogeneousTransform",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkInertias" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_fromHomogeneousTransform" "', argument " "1"" of type '" "iDynTree::Transform *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_fromHomogeneousTransform" "', argument " "2"" of type '" "iDynTree::Matrix4x4 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_fromHomogeneousTransform" "', argument " "2"" of type '" "iDynTree::Matrix4x4 const &""'"); } + arg2 = reinterpret_cast< iDynTree::Matrix4x4 * >(argp2); + (arg1)->fromHomogeneousTransform((iDynTree::Matrix4x4 const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -40397,23 +38171,23 @@ int _wrap_delete_LinkInertias(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_LinkArticulatedBodyInertias__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Transform_getRotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkArticulatedBodyInertias *result = 0 ; + iDynTree::Rotation *result = 0 ; - if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_getRotation",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_getRotation" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = (iDynTree::Rotation *) &((iDynTree::Transform const *)arg1)->getRotation(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Rotation, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40421,16 +38195,23 @@ int _wrap_new_LinkArticulatedBodyInertias__SWIG_0(int resc, mxArray *resv[], int } -int _wrap_new_LinkArticulatedBodyInertias__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Transform_getPosition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkArticulatedBodyInertias *result = 0 ; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,0,0,0)) { + if (!SWIG_check_num_args("Transform_getPosition",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_getPosition" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = (iDynTree::Position *) &((iDynTree::Transform const *)arg1)->getPosition(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40438,26 +38219,33 @@ int _wrap_new_LinkArticulatedBodyInertias__SWIG_1(int resc, mxArray *resv[], int } -int _wrap_new_LinkArticulatedBodyInertias__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Transform_setRotation(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Rotation *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkArticulatedBodyInertias *result = 0 ; - if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_setRotation",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_setRotation" "', argument " "1"" of type '" "iDynTree::Transform *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Rotation, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_setRotation" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_setRotation" "', argument " "2"" of type '" "iDynTree::Rotation const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Rotation * >(argp2); + (arg1)->setRotation((iDynTree::Rotation const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40465,62 +38253,32 @@ int _wrap_new_LinkArticulatedBodyInertias__SWIG_2(int resc, mxArray *resv[], int } -int _wrap_new_LinkArticulatedBodyInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkArticulatedBodyInertias__SWIG_1(resc,resv,argc,argv); +int _wrap_Transform_setPosition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Position *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("Transform_setPosition",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkArticulatedBodyInertias__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_setPosition" "', argument " "1"" of type '" "iDynTree::Transform *""'"); } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkArticulatedBodyInertias__SWIG_0(resc,resv,argc,argv); - } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_setPosition" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkArticulatedBodyInertias'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias(std::size_t)\n" - " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias()\n" - " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkArticulatedBodyInertias_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("LinkArticulatedBodyInertias_resize",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_setPosition" "', argument " "2"" of type '" "iDynTree::Position const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + (arg1)->setPosition((iDynTree::Position const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -40529,33 +38287,37 @@ int _wrap_LinkArticulatedBodyInertias_resize__SWIG_0(int resc, mxArray *resv[], } -int _wrap_LinkArticulatedBodyInertias_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_Transform_compose(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = 0 ; + iDynTree::Transform *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Transform result; - if (!SWIG_check_num_args("LinkArticulatedBodyInertias_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_compose",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_compose" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_compose" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_compose" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_compose" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = iDynTree::Transform::compose((iDynTree::Transform const &)*arg1,(iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40563,73 +38325,61 @@ int _wrap_LinkArticulatedBodyInertias_resize__SWIG_1(int resc, mxArray *resv[], } -int _wrap_LinkArticulatedBodyInertias_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkArticulatedBodyInertias_resize__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_Transform_inverse2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Transform result; + + if (!SWIG_check_num_args("Transform_inverse2",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkArticulatedBodyInertias_resize__SWIG_0(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_inverse2" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkArticulatedBodyInertias_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkArticulatedBodyInertias::resize(std::size_t)\n" - " iDynTree::LinkArticulatedBodyInertias::resize(iDynTree::Model const &)\n"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_inverse2" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = iDynTree::Transform::inverse2((iDynTree::Transform const &)*arg1); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinkArticulatedBodyInertias_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Transform_mtimes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Transform result; - if (!SWIG_check_num_args("LinkArticulatedBodyInertias_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkArticulatedBodyInertias const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40637,31 +38387,23 @@ int _wrap_LinkArticulatedBodyInertias_isConsistent(int resc, mxArray *resv[], in } -int _wrap_LinkArticulatedBodyInertias_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_Transform_inverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + iDynTree::Transform result; - if (!SWIG_check_num_args("LinkArticulatedBodyInertias_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_inverse",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_inverse" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::ArticulatedBodyInertia *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->inverse(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40669,31 +38411,34 @@ int _wrap_LinkArticulatedBodyInertias_paren__SWIG_0(int resc, mxArray *resv[], i } -int _wrap_LinkArticulatedBodyInertias_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_Transform_mtimes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Position *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyInertia *result = 0 ; + iDynTree::Position result; - if (!SWIG_check_num_args("LinkArticulatedBodyInertias_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::ArticulatedBodyInertia *) &((iDynTree::LinkArticulatedBodyInertias const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Position, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Position const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Position * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Position const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40701,66 +38446,34 @@ int _wrap_LinkArticulatedBodyInertias_paren__SWIG_1(int resc, mxArray *resv[], i } -int _wrap_LinkArticulatedBodyInertias_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkArticulatedBodyInertias_paren__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkArticulatedBodyInertias_paren__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkArticulatedBodyInertias_paren'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkArticulatedBodyInertias::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkArticulatedBodyInertias::operator ()(iDynTree::LinkIndex const) const\n"); - return 1; -} - - -int _wrap_delete_LinkArticulatedBodyInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; +int _wrap_Transform_mtimes__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Wrench *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::Wrench result; - int is_owned; - if (!SWIG_check_num_args("delete_LinkArticulatedBodyInertias",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); } - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Wrench const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Wrench * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Wrench const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40768,23 +38481,34 @@ int _wrap_delete_LinkArticulatedBodyInertias(int resc, mxArray *resv[], int argc } -int _wrap_new_LinkVelArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Transform_mtimes__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Twist *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkVelArray *result = 0 ; + iDynTree::Twist result; - if (!SWIG_check_num_args("new_LinkVelArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Twist(static_cast< const iDynTree::Twist& >(result))), SWIGTYPE_p_iDynTree__Twist, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40792,16 +38516,34 @@ int _wrap_new_LinkVelArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkVelArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Transform_mtimes__SWIG_4(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::SpatialMomentum *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkVelArray *result = 0 ; + iDynTree::SpatialMomentum result; - if (!SWIG_check_num_args("new_LinkVelArray",argc,0,0,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMomentum const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialMomentum const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMomentum(static_cast< const iDynTree::SpatialMomentum& >(result))), SWIGTYPE_p_iDynTree__SpatialMomentum, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40809,26 +38551,34 @@ int _wrap_new_LinkVelArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkVelArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Transform_mtimes__SWIG_5(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkVelArray *result = 0 ; + iDynTree::SpatialAcc result; - if (!SWIG_check_num_args("new_LinkVelArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialAcc(static_cast< const iDynTree::SpatialAcc& >(result))), SWIGTYPE_p_iDynTree__SpatialAcc, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40836,63 +38586,69 @@ int _wrap_new_LinkVelArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkVelArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkVelArray__SWIG_1(resc,resv,argc,argv); +int _wrap_Transform_mtimes__SWIG_6(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::SpatialMotionVector *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + iDynTree::SpatialMotionVector result; + + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkVelArray__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkVelArray__SWIG_0(resc,resv,argc,argv); - } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkVelArray'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkVelArray::LinkVelArray(std::size_t)\n" - " iDynTree::LinkVelArray::LinkVelArray()\n" - " iDynTree::LinkVelArray::LinkVelArray(iDynTree::Model const &)\n"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialMotionVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialMotionVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinkVelArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - std::size_t arg2 ; +int _wrap_Transform_mtimes__SWIG_7(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::SpatialForceVector *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + iDynTree::SpatialForceVector result; - if (!SWIG_check_num_args("LinkVelArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_resize" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialForceVector const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialForceVector const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40900,33 +38656,34 @@ int _wrap_LinkVelArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkVelArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Transform_mtimes__SWIG_8(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::SpatialInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::SpatialInertia result; - if (!SWIG_check_num_args("LinkVelArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_resize" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::SpatialInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::SpatialInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::SpatialInertia(static_cast< const iDynTree::SpatialInertia& >(result))), SWIGTYPE_p_iDynTree__SpatialInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -40934,73 +38691,34 @@ int _wrap_LinkVelArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkVelArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkVelArray_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkVelArray_resize__SWIG_0(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkVelArray_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkVelArray::resize(std::size_t)\n" - " iDynTree::LinkVelArray::resize(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkVelArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Transform_mtimes__SWIG_9(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::ArticulatedBodyInertia *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::ArticulatedBodyInertia result; - if (!SWIG_check_num_args("LinkVelArray_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::ArticulatedBodyInertia const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkVelArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::ArticulatedBodyInertia const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41008,55 +38726,34 @@ int _wrap_LinkVelArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkVelArray_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; +int _wrap_Transform_mtimes__SWIG_10(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Direction *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - size_t result; + iDynTree::Direction result; - if (!SWIG_check_num_args("LinkVelArray_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - result = ((iDynTree::LinkVelArray const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_LinkVelArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - iDynTree::Twist *result = 0 ; - - if (!SWIG_check_num_args("LinkVelArray_paren",argc,2,2,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Direction, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_paren" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Direction const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Twist *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Direction * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Direction const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Direction(static_cast< const iDynTree::Direction& >(result))), SWIGTYPE_p_iDynTree__Direction, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41064,31 +38761,34 @@ int _wrap_LinkVelArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkVelArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_Transform_mtimes__SWIG_11(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + iDynTree::Axis *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Twist *result = 0 ; + iDynTree::Axis result; - if (!SWIG_check_num_args("LinkVelArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_paren" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_mtimes" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::Twist *) &((iDynTree::LinkVelArray const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Axis, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Transform_mtimes" "', argument " "2"" of type '" "iDynTree::Axis const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Axis * >(argp2); + result = ((iDynTree::Transform const *)arg1)->operator *((iDynTree::Axis const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Axis(static_cast< const iDynTree::Axis& >(result))), SWIGTYPE_p_iDynTree__Axis, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41096,74 +38796,204 @@ int _wrap_LinkVelArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkVelArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Transform_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_0(resc,resv,argc,argv); } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Position, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkVelArray_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_Transform_mtimes__SWIG_1(resc,resv,argc,argv); } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_2(resc,resv,argc,argv); } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Twist, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkVelArray_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_Transform_mtimes__SWIG_3(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMomentum, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_4(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_5(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_6(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_7(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SpatialInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_8(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_9(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Direction, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_10(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Axis, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Transform_mtimes__SWIG_11(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkVelArray_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Transform_mtimes'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkVelArray::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkVelArray::operator ()(iDynTree::LinkIndex const) const\n"); + " iDynTree::Transform::operator *(iDynTree::Transform const &) const\n" + " iDynTree::Transform::operator *(iDynTree::Position const &) const\n" + " iDynTree::Transform::operator *(iDynTree::Wrench const &) const\n" + " iDynTree::Transform::operator *(iDynTree::Twist const &) const\n" + " iDynTree::Transform::operator *(iDynTree::SpatialMomentum const &) const\n" + " iDynTree::Transform::operator *(iDynTree::SpatialAcc const &) const\n" + " iDynTree::Transform::operator *(iDynTree::SpatialMotionVector const &) const\n" + " iDynTree::Transform::operator *(iDynTree::SpatialForceVector const &) const\n" + " iDynTree::Transform::operator *(iDynTree::SpatialInertia const &) const\n" + " iDynTree::Transform::operator *(iDynTree::ArticulatedBodyInertia const &) const\n" + " iDynTree::Transform::operator *(iDynTree::Direction const &) const\n" + " iDynTree::Transform::operator *(iDynTree::Axis const &) const\n"); return 1; } -int _wrap_LinkVelArray_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_Transform_Identity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::string result; + iDynTree::Transform result; - if (!SWIG_check_num_args("LinkVelArray_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_Identity",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_toString" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::LinkVelArray const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + (void)argv; + result = iDynTree::Transform::Identity(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41171,26 +39001,23 @@ int _wrap_LinkVelArray_toString(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_delete_LinkVelArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; +int _wrap_Transform_asHomogeneousTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::Matrix4x4 result; - int is_owned; - if (!SWIG_check_num_args("delete_LinkVelArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_asHomogeneousTransform",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkVelArray" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asHomogeneousTransform" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->asHomogeneousTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix4x4(static_cast< const iDynTree::Matrix4x4& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41198,23 +39025,23 @@ int _wrap_delete_LinkVelArray(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_LinkAccArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Transform_asAdjointTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkAccArray *result = 0 ; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("new_LinkAccArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_asAdjointTransform",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asAdjointTransform" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->asAdjointTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41222,16 +39049,23 @@ int _wrap_new_LinkAccArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkAccArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Transform_asAdjointTransformWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::LinkAccArray *result = 0 ; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("new_LinkAccArray",argc,0,0,0)) { + if (!SWIG_check_num_args("Transform_asAdjointTransformWrench",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_asAdjointTransformWrench" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->asAdjointTransformWrench(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41239,26 +39073,23 @@ int _wrap_new_LinkAccArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkAccArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Transform_log(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkAccArray *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("new_LinkAccArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Transform_log",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_log" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->log(); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41266,63 +39097,23 @@ int _wrap_new_LinkAccArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_LinkAccArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinkAccArray__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinkAccArray__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinkAccArray__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkAccArray'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkAccArray::LinkAccArray(std::size_t)\n" - " iDynTree::LinkAccArray::LinkAccArray()\n" - " iDynTree::LinkAccArray::LinkAccArray(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkAccArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - std::size_t arg2 ; +int _wrap_Transform_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("LinkAccArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_resize" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_toString" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41330,33 +39121,23 @@ int _wrap_LinkAccArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkAccArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Transform_display(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("LinkAccArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Transform_display",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_resize" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Transform_display" "', argument " "1"" of type '" "iDynTree::Transform const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = ((iDynTree::Transform const *)arg1)->reservedToString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41364,73 +39145,43 @@ int _wrap_LinkAccArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinkAccArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkAccArray_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkAccArray_resize__SWIG_0(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkAccArray_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkAccArray::resize(std::size_t)\n" - " iDynTree::LinkAccArray::resize(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkAccArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_delete_Transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = (iDynTree::Transform *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("LinkAccArray_isConsistent",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Transform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Transform" "', argument " "1"" of type '" "iDynTree::Transform *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + if (is_owned) { + delete arg1; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_TransformDerivative__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::TransformDerivative *result = 0 ; + + if (!SWIG_check_num_args("new_TransformDerivative",argc,0,0,0)) { + SWIG_fail; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkAccArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + (void)argv; + result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41438,31 +39189,37 @@ int _wrap_LinkAccArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkAccArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; +int _wrap_new_TransformDerivative__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Matrix3x3 *arg1 = 0 ; + iDynTree::Vector3 *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::TransformDerivative *result = 0 ; - if (!SWIG_check_num_args("LinkAccArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("new_TransformDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_paren" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::Matrix3x3 const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::SpatialAcc *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::Matrix3x3 const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Matrix3x3 * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_TransformDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); + result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative((iDynTree::Matrix3x3 const &)*arg1,(iDynTree::Vector3 const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41470,31 +39227,26 @@ int _wrap_LinkAccArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkAccArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; +int _wrap_new_TransformDerivative__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::TransformDerivative *result = 0 ; - if (!SWIG_check_num_args("LinkAccArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("new_TransformDerivative",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__TransformDerivative, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_paren" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::SpatialAcc *) &((iDynTree::LinkAccArray const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const &""'"); + } + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + result = (iDynTree::TransformDerivative *)new iDynTree::TransformDerivative((iDynTree::TransformDerivative const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__TransformDerivative, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41502,63 +39254,63 @@ int _wrap_LinkAccArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinkAccArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_TransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_TransformDerivative__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkAccArray_paren__SWIG_0(resc,resv,argc,argv); - } + return _wrap_new_TransformDerivative__SWIG_2(resc,resv,argc,argv); } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_LinkAccArray_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_new_TransformDerivative__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkAccArray_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_TransformDerivative'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkAccArray::operator ()(iDynTree::LinkIndex const)\n" - " iDynTree::LinkAccArray::operator ()(iDynTree::LinkIndex const) const\n"); + " iDynTree::TransformDerivative::TransformDerivative()\n" + " iDynTree::TransformDerivative::TransformDerivative(iDynTree::Matrix3x3 const &,iDynTree::Vector3 const &)\n" + " iDynTree::TransformDerivative::TransformDerivative(iDynTree::TransformDerivative const &)\n"); return 1; } -int _wrap_LinkAccArray_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; +int _wrap_delete_TransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("LinkAccArray_getNrOfLinks",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_TransformDerivative",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_TransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - result = ((iDynTree::LinkAccArray const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41566,34 +39318,23 @@ int _wrap_LinkAccArray_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinkAccArray_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_TransformDerivative_getRotationDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - std::string result; + iDynTree::Matrix3x3 *result = 0 ; - if (!SWIG_check_num_args("LinkAccArray_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("TransformDerivative_getRotationDerivative",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_toString" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_getRotationDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::LinkAccArray const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + result = (iDynTree::Matrix3x3 *) &((iDynTree::TransformDerivative const *)arg1)->getRotationDerivative(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41601,26 +39342,23 @@ int _wrap_LinkAccArray_toString(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_delete_LinkAccArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; +int _wrap_TransformDerivative_getPositionDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::Vector3 *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_LinkAccArray",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_getPositionDerivative",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkAccArray" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_getPositionDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + result = (iDynTree::Vector3 *) &((iDynTree::TransformDerivative const *)arg1)->getPositionDerivative(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41628,16 +39366,33 @@ int _wrap_delete_LinkAccArray(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_new_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_TransformDerivative_setRotationDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Matrix3x3 *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Link *result = 0 ; - if (!SWIG_check_num_args("new_Link",argc,0,0,0)) { + if (!SWIG_check_num_args("TransformDerivative_setRotationDerivative",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Link *)new iDynTree::Link(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_setRotationDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); + } + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__MatrixFixSizeT_3_3_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_setRotationDerivative" "', argument " "2"" of type '" "iDynTree::Matrix3x3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_setRotationDerivative" "', argument " "2"" of type '" "iDynTree::Matrix3x3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Matrix3x3 * >(argp2); + (arg1)->setRotationDerivative((iDynTree::Matrix3x3 const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41645,23 +39400,33 @@ int _wrap_new_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Link_inertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; +int _wrap_TransformDerivative_setPositionDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Vector3 *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; - if (!SWIG_check_num_args("Link_inertia",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_setPositionDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_inertia" "', argument " "1"" of type '" "iDynTree::Link *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_setPositionDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - result = (iDynTree::SpatialInertia *) &(arg1)->inertia(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_setPositionDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_setPositionDerivative" "', argument " "2"" of type '" "iDynTree::Vector3 const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Vector3 * >(argp2); + (arg1)->setPositionDerivative((iDynTree::Vector3 const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41669,23 +39434,16 @@ int _wrap_Link_inertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Link_inertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_TransformDerivative_Zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Link_inertia",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_Zero",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_inertia" "', argument " "1"" of type '" "iDynTree::Link const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - result = (iDynTree::SpatialInertia *) &((iDynTree::Link const *)arg1)->inertia(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + (void)argv; + result = iDynTree::TransformDerivative::Zero(); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41693,61 +39451,58 @@ int _wrap_Link_inertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Link_inertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Link, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Link_inertia__SWIG_0(resc,resv,argc,argv); - } +int _wrap_TransformDerivative_asHomogeneousTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Matrix4x4 result; + + if (!SWIG_check_num_args("TransformDerivative_asHomogeneousTransformDerivative",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Link, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Link_inertia__SWIG_1(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asHomogeneousTransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Link_inertia'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Link::inertia()\n" - " iDynTree::Link::inertia() const\n"); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + result = ((iDynTree::TransformDerivative const *)arg1)->asHomogeneousTransformDerivative(); + _out = SWIG_NewPointerObj((new iDynTree::Matrix4x4(static_cast< const iDynTree::Matrix4x4& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_4_4_t, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_Link_setInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; - iDynTree::SpatialInertia *arg2 = 0 ; +int _wrap_TransformDerivative_asAdjointTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Link_setInertia",argc,2,2,0)) { + if (!SWIG_check_num_args("TransformDerivative_asAdjointTransformDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_setInertia" "', argument " "1"" of type '" "iDynTree::Link *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Link_setInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Link_setInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_asAdjointTransformDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); - (arg1)->setInertia(*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = ((iDynTree::TransformDerivative const *)arg1)->asAdjointTransformDerivative((iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41755,23 +39510,34 @@ int _wrap_Link_setInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Link_getInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; +int _wrap_TransformDerivative_asAdjointTransformWrenchDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SpatialInertia *result = 0 ; + iDynTree::Matrix6x6 result; - if (!SWIG_check_num_args("Link_getInertia",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_asAdjointTransformWrenchDerivative",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_getInertia" "', argument " "1"" of type '" "iDynTree::Link const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - result = (iDynTree::SpatialInertia *) &((iDynTree::Link const *)arg1)->getInertia(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_asAdjointTransformWrenchDerivative" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = ((iDynTree::TransformDerivative const *)arg1)->asAdjointTransformWrenchDerivative((iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Matrix6x6(static_cast< const iDynTree::Matrix6x6& >(result))), SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41779,33 +39545,34 @@ int _wrap_Link_getInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_Link_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_TransformDerivative_mtimes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Link_setIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("TransformDerivative_mtimes",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_setIndex" "', argument " "1"" of type '" "iDynTree::Link *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_mtimes" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Link_setIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Link_setIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_mtimes" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg2 = reinterpret_cast< iDynTree::LinkIndex * >(argp2); - (arg1)->setIndex(*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = ((iDynTree::TransformDerivative const *)arg1)->operator *((iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41813,23 +39580,34 @@ int _wrap_Link_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Link_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; +int _wrap_TransformDerivative_derivativeOfInverse(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::TransformDerivative result; - if (!SWIG_check_num_args("Link_getIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_derivativeOfInverse",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_getIndex" "', argument " "1"" of type '" "iDynTree::Link const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "1"" of type '" "iDynTree::TransformDerivative const *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - result = ((iDynTree::Link const *)arg1)->getIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_derivativeOfInverse" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = ((iDynTree::TransformDerivative const *)arg1)->derivativeOfInverse((iDynTree::Transform const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41837,26 +39615,45 @@ int _wrap_Link_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; +int _wrap_TransformDerivative_transform__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; + iDynTree::ArticulatedBodyInertia *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + iDynTree::ArticulatedBodyInertia result; - int is_owned; - if (!SWIG_check_num_args("delete_Link",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Link" "', argument " "1"" of type '" "iDynTree::Link *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); } - arg1 = reinterpret_cast< iDynTree::Link * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::ArticulatedBodyInertia &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::ArticulatedBodyInertia &""'"); + } + arg3 = reinterpret_cast< iDynTree::ArticulatedBodyInertia * >(argp3); + result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); + _out = SWIG_NewPointerObj((new iDynTree::ArticulatedBodyInertia(static_cast< const iDynTree::ArticulatedBodyInertia& >(result))), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41864,26 +39661,45 @@ int _wrap_delete_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_IJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_TransformDerivative_transform__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; + iDynTree::SpatialForceVector *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; + iDynTree::SpatialForceVector result; - int is_owned; - if (!SWIG_check_num_args("delete_IJoint",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_IJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialForceVector, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialForceVector &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialForceVector &""'"); + } + arg3 = reinterpret_cast< iDynTree::SpatialForceVector * >(argp3); + result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); + _out = SWIG_NewPointerObj((new iDynTree::SpatialForceVector(static_cast< const iDynTree::SpatialForceVector& >(result))), SWIGTYPE_p_iDynTree__SpatialForceVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41891,23 +39707,45 @@ int _wrap_delete_IJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_IJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_TransformDerivative_transform__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::TransformDerivative *arg1 = (iDynTree::TransformDerivative *) 0 ; + iDynTree::Transform *arg2 = 0 ; + iDynTree::SpatialMotionVector *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::IJoint *result = 0 ; + iDynTree::SpatialMotionVector result; - if (!SWIG_check_num_args("IJoint_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformDerivative_transform",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__TransformDerivative, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_clone" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "TransformDerivative_transform" "', argument " "1"" of type '" "iDynTree::TransformDerivative *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (iDynTree::IJoint *)((iDynTree::IJoint const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::TransformDerivative * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialMotionVector &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "TransformDerivative_transform" "', argument " "3"" of type '" "iDynTree::SpatialMotionVector &""'"); + } + arg3 = reinterpret_cast< iDynTree::SpatialMotionVector * >(argp3); + result = (arg1)->transform((iDynTree::Transform const &)*arg2,*arg3); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41915,47 +39753,90 @@ int _wrap_IJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_IJoint_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - unsigned int result; - - if (!SWIG_check_num_args("IJoint_getNrOfPosCoords",argc,1,1,0)) { - SWIG_fail; +int _wrap_TransformDerivative_transform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_TransformDerivative_transform__SWIG_0(resc,resv,argc,argv); + } + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SpatialForceVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_TransformDerivative_transform__SWIG_1(resc,resv,argc,argv); + } + } + } } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (unsigned int)((iDynTree::IJoint const *)arg1)->getNrOfPosCoords(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__TransformDerivative, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SpatialMotionVector, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_TransformDerivative_transform__SWIG_2(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'TransformDerivative_transform'." + " Possible C/C++ prototypes are:\n" + " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::ArticulatedBodyInertia &)\n" + " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::SpatialForceVector &)\n" + " iDynTree::TransformDerivative::transform(iDynTree::Transform const &,iDynTree::SpatialMotionVector &)\n"); return 1; } -int _wrap_IJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +SWIGINTERN int _wrap_dynamic_extent_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::dynamic_extent)); + return 0; +} + + +int _wrap_DynamicSpan_extent_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - unsigned int result; + iDynTree::Span< double,-1 >::index_type result; - if (!SWIG_check_num_args("IJoint_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicSpan_extent_get",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (unsigned int)((iDynTree::IJoint const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + (void)argv; + result = (iDynTree::Span< double,-1 >::index_type)iDynTree::Span< double,-1 >::extent; + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -41963,38 +39844,31 @@ int _wrap_IJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_IJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::LinkIndex arg3 ; +int _wrap_new_DynamicSpan__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 >::pointer arg1 = (iDynTree::Span< double,-1 >::pointer) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 > *result = 0 ; - if (!SWIG_check_num_args("IJoint_setAttachedLinks",argc,3,3,0)) { + if (!SWIG_check_num_args("new_DynamicSpan",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setAttachedLinks" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setAttachedLinks" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_setAttachedLinks" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicSpan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - (arg1)->setAttachedLinks(arg2,arg3); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42002,33 +39876,31 @@ int _wrap_IJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_IJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_new_DynamicSpan__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 >::pointer arg1 = (iDynTree::Span< double,-1 >::pointer) 0 ; + iDynTree::Span< double,-1 >::pointer arg2 = (iDynTree::Span< double,-1 >::pointer) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 > *result = 0 ; - if (!SWIG_check_num_args("IJoint_setRestTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("new_DynamicSpan",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setRestTransform" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_DynamicSpan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::pointer""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - (arg1)->setRestTransform((iDynTree::Transform const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::Span< double,-1 >::pointer >(argp2); + result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42036,23 +39908,26 @@ int _wrap_IJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_IJoint_getFirstAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; +int _wrap_new_DynamicSpan__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::Span< double,-1 > *result = 0 ; - if (!SWIG_check_num_args("IJoint_getFirstAttachedLink",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DynamicSpan",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getFirstAttachedLink" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const &""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = ((iDynTree::IJoint const *)arg1)->getFirstAttachedLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = (iDynTree::Span< double,-1 > *)new iDynTree::Span< double,-1 >((iDynTree::Span< double,-1 > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpanT_double__1_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42060,23 +39935,75 @@ int _wrap_IJoint_getFirstAttachedLink(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_IJoint_getSecondAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_new_DynamicSpan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_DynamicSpan__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_DynamicSpan__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_DynamicSpan__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DynamicSpan'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 >::pointer,iDynTree::Span< double,-1 >::index_type)\n" + " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 >::pointer,iDynTree::Span< double,-1 >::pointer)\n" + " iDynTree::Span< double,-1 >::Span(iDynTree::Span< double,-1 > const &)\n"); + return 1; +} + + +int _wrap_delete_DynamicSpan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; - if (!SWIG_check_num_args("IJoint_getSecondAttachedLink",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_DynamicSpan",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getSecondAttachedLink" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DynamicSpan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = ((iDynTree::IJoint const *)arg1)->getSecondAttachedLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42084,39 +40011,31 @@ int _wrap_IJoint_getSecondAttachedLink(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_IJoint_getRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::LinkIndex arg3 ; +int _wrap_DynamicSpan_first(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::Transform result; + SwigValueWrapper< iDynTree::Span< double,-1 > > result; - if (!SWIG_check_num_args("IJoint_getRestTransform",argc,3,3,0)) { + if (!SWIG_check_num_args("DynamicSpan_first",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getRestTransform" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_first" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getRestTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getRestTransform" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_first" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - result = ((iDynTree::IJoint const *)arg1)->getRestTransform(arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = ((iDynTree::Span< double,-1 > const *)arg1)->first(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42124,50 +40043,31 @@ int _wrap_IJoint_getRestTransform(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_IJoint_getTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::LinkIndex arg3 ; - iDynTree::LinkIndex arg4 ; +int _wrap_DynamicSpan_last(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - ptrdiff_t val4 ; - int ecode4 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + SwigValueWrapper< iDynTree::Span< double,-1 > > result; - if (!SWIG_check_num_args("IJoint_getTransform",argc,4,4,0)) { + if (!SWIG_check_num_args("DynamicSpan_last",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getTransform" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_getTransform" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getTransform" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_last" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getTransform" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); - } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getTransform" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_last" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg4 = static_cast< iDynTree::LinkIndex >(val4); - result = (iDynTree::Transform *) &((iDynTree::IJoint const *)arg1)->getTransform((iDynTree::VectorDynSize const &)*arg2,arg3,arg4); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = ((iDynTree::Span< double,-1 > const *)arg1)->last(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42175,58 +40075,39 @@ int _wrap_IJoint_getTransform(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_IJoint_getTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::LinkIndex arg3 ; - iDynTree::LinkIndex arg4 ; - int arg5 ; +int _wrap_DynamicSpan_subspan__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; + iDynTree::Span< double,-1 >::index_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; ptrdiff_t val3 ; int ecode3 = 0 ; - ptrdiff_t val4 ; - int ecode4 = 0 ; - int val5 ; - int ecode5 = 0 ; mxArray * _out; - iDynTree::TransformDerivative result; + SwigValueWrapper< iDynTree::Span< double,-1 > > result; - if (!SWIG_check_num_args("IJoint_getTransformDerivative",argc,5,5,0)) { + if (!SWIG_check_num_args("DynamicSpan_subspan",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getTransformDerivative" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_getTransformDerivative" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getTransformDerivative" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_subspan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_subspan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); + } + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getTransformDerivative" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicSpan_subspan" "', argument " "3"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getTransformDerivative" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); - } - arg4 = static_cast< iDynTree::LinkIndex >(val4); - ecode5 = SWIG_AsVal_int(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_getTransformDerivative" "', argument " "5"" of type '" "int""'"); - } - arg5 = static_cast< int >(val5); - result = ((iDynTree::IJoint const *)arg1)->getTransformDerivative((iDynTree::VectorDynSize const &)*arg2,arg3,arg4,arg5); - _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + arg3 = static_cast< iDynTree::Span< double,-1 >::index_type >(val3); + result = ((iDynTree::Span< double,-1 > const *)arg1)->subspan(arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42234,47 +40115,31 @@ int _wrap_IJoint_getTransformDerivative(int resc, mxArray *resv[], int argc, mxA } -int _wrap_IJoint_getMotionSubspaceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - int arg2 ; - iDynTree::LinkIndex arg3 ; - iDynTree::LinkIndex arg4 ; +int _wrap_DynamicSpan_subspan__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - ptrdiff_t val4 ; - int ecode4 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector result; + SwigValueWrapper< iDynTree::Span< double,-1 > > result; - if (!SWIG_check_num_args("IJoint_getMotionSubspaceVector",argc,4,4,0)) { + if (!SWIG_check_num_args("DynamicSpan_subspan",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_subspan" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "2"" of type '" "int""'"); - } - arg2 = static_cast< int >(val2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); - } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_subspan" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg4 = static_cast< iDynTree::LinkIndex >(val4); - result = ((iDynTree::IJoint const *)arg1)->getMotionSubspaceVector(arg2,arg3,arg4); - _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = ((iDynTree::Span< double,-1 > const *)arg1)->subspan(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >(static_cast< const iDynTree::Span< iDynTree::Span< double,-1 >::element_type,-1 >& >(result))), SWIGTYPE_p_iDynTree__SpanT_double__1_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42282,104 +40147,69 @@ int _wrap_IJoint_getMotionSubspaceVector(int resc, mxArray *resv[], int argc, mx } -int _wrap_IJoint_computeChildPosVelAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::VectorDynSize *arg3 = 0 ; - iDynTree::VectorDynSize *arg4 = 0 ; - iDynTree::LinkPositions *arg5 = 0 ; - iDynTree::LinkVelArray *arg6 = 0 ; - iDynTree::LinkAccArray *arg7 = 0 ; - iDynTree::LinkIndex arg8 ; - iDynTree::LinkIndex arg9 ; +int _wrap_DynamicSpan_subspan(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DynamicSpan_subspan__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DynamicSpan_subspan__SWIG_0(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DynamicSpan_subspan'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Span< double,-1 >::subspan(iDynTree::Span< double,-1 >::index_type,iDynTree::Span< double,-1 >::index_type) const\n" + " iDynTree::Span< double,-1 >::subspan(iDynTree::Span< double,-1 >::index_type) const\n"); + return 1; +} + + +int _wrap_DynamicSpan_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; - ptrdiff_t val8 ; - int ecode8 = 0 ; - ptrdiff_t val9 ; - int ecode9 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 >::index_type result; - if (!SWIG_check_num_args("IJoint_computeChildPosVelAcc",argc,9,9,0)) { + if (!SWIG_check_num_args("DynamicSpan_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_size" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); - ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); - if (!SWIG_IsOK(ecode8)) { - SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); - } - arg8 = static_cast< iDynTree::LinkIndex >(val8); - ecode9 = SWIG_AsVal_ptrdiff_t(argv[8], &val9); - if (!SWIG_IsOK(ecode9)) { - SWIG_exception_fail(SWIG_ArgError(ecode9), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "9"" of type '" "iDynTree::LinkIndex""'"); - } - arg9 = static_cast< iDynTree::LinkIndex >(val9); - ((iDynTree::IJoint const *)arg1)->computeChildPosVelAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5,*arg6,*arg7,arg8,arg9); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->size(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42387,93 +40217,23 @@ int _wrap_IJoint_computeChildPosVelAcc(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_IJoint_computeChildVelAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::VectorDynSize *arg3 = 0 ; - iDynTree::VectorDynSize *arg4 = 0 ; - iDynTree::LinkVelArray *arg5 = 0 ; - iDynTree::LinkAccArray *arg6 = 0 ; - iDynTree::LinkIndex arg7 ; - iDynTree::LinkIndex arg8 ; +int _wrap_DynamicSpan_size_bytes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; - ptrdiff_t val7 ; - int ecode7 = 0 ; - ptrdiff_t val8 ; - int ecode8 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 >::index_type result; - if (!SWIG_check_num_args("IJoint_computeChildVelAcc",argc,8,8,0)) { + if (!SWIG_check_num_args("DynamicSpan_size_bytes",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildVelAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildVelAcc" "', argument " "5"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "5"" of type '" "iDynTree::LinkVelArray &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkVelArray * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildVelAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_size_bytes" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); - ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); - if (!SWIG_IsOK(ecode7)) { - SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildVelAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); - } - arg7 = static_cast< iDynTree::LinkIndex >(val7); - ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); - if (!SWIG_IsOK(ecode8)) { - SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildVelAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); - } - arg8 = static_cast< iDynTree::LinkIndex >(val8); - ((iDynTree::IJoint const *)arg1)->computeChildVelAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5,*arg6,arg7,arg8); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->size_bytes(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42481,71 +40241,55 @@ int _wrap_IJoint_computeChildVelAcc(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_IJoint_computeChildVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::VectorDynSize *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::LinkIndex arg5 ; - iDynTree::LinkIndex arg6 ; +int _wrap_DynamicSpan_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; - ptrdiff_t val5 ; - int ecode5 = 0 ; - ptrdiff_t val6 ; - int ecode6 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("IJoint_computeChildVel",argc,6,6,0)) { + if (!SWIG_check_num_args("DynamicSpan_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildVel" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildVel" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildVel" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_empty" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildVel" "', argument " "4"" of type '" "iDynTree::LinkVelArray &""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = (bool)((iDynTree::Span< double,-1 > const *)arg1)->empty(); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_DynamicSpan_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Span< double,-1 >::element_type *result = 0 ; + + if (!SWIG_check_num_args("DynamicSpan_brace",argc,2,2,0)) { + SWIG_fail; } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "4"" of type '" "iDynTree::LinkVelArray &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_brace" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_computeChildVel" "', argument " "5"" of type '" "iDynTree::LinkIndex""'"); - } - arg5 = static_cast< iDynTree::LinkIndex >(val5); - ecode6 = SWIG_AsVal_ptrdiff_t(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "IJoint_computeChildVel" "', argument " "6"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_brace" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg6 = static_cast< iDynTree::LinkIndex >(val6); - ((iDynTree::IJoint const *)arg1)->computeChildVel((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,*arg4,arg5,arg6); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->operator [](arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42553,93 +40297,31 @@ int _wrap_IJoint_computeChildVel(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_IJoint_computeChildAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::VectorDynSize *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::VectorDynSize *arg5 = 0 ; - iDynTree::LinkAccArray *arg6 = 0 ; - iDynTree::LinkIndex arg7 ; - iDynTree::LinkIndex arg8 ; +int _wrap_DynamicSpan_getVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; - ptrdiff_t val7 ; - int ecode7 = 0 ; - ptrdiff_t val8 ; - int ecode8 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 >::element_type *result = 0 ; - if (!SWIG_check_num_args("IJoint_computeChildAcc",argc,8,8,0)) { + if (!SWIG_check_num_args("DynamicSpan_getVal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildAcc" "', argument " "5"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "5"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg5 = reinterpret_cast< iDynTree::VectorDynSize * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_getVal" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); - ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); - if (!SWIG_IsOK(ecode7)) { - SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); - } - arg7 = static_cast< iDynTree::LinkIndex >(val7); - ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); - if (!SWIG_IsOK(ecode8)) { - SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_getVal" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg8 = static_cast< iDynTree::LinkIndex >(val8); - ((iDynTree::IJoint const *)arg1)->computeChildAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::VectorDynSize const &)*arg5,*arg6,arg7,arg8); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->getVal(arg2); + _out = SWIG_From_double(static_cast< double >(*result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42647,82 +40329,41 @@ int _wrap_IJoint_computeChildAcc(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_IJoint_computeChildBiasAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::VectorDynSize *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::LinkAccArray *arg5 = 0 ; - iDynTree::LinkIndex arg6 ; - iDynTree::LinkIndex arg7 ; +int _wrap_DynamicSpan_setVal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; + iDynTree::Span< double,-1 >::element_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; - ptrdiff_t val6 ; - int ecode6 = 0 ; - ptrdiff_t val7 ; - int ecode7 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + double temp3 ; + double val3 ; + int ecode3 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("IJoint_computeChildBiasAcc",argc,7,7,0)) { + if (!SWIG_check_num_args("DynamicSpan_setVal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildBiasAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_setVal" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildBiasAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildBiasAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildBiasAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildBiasAcc" "', argument " "5"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "5"" of type '" "iDynTree::LinkAccArray &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); - ecode6 = SWIG_AsVal_ptrdiff_t(argv[5], &val6); - if (!SWIG_IsOK(ecode6)) { - SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "IJoint_computeChildBiasAcc" "', argument " "6"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_setVal" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg6 = static_cast< iDynTree::LinkIndex >(val6); - ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); - if (!SWIG_IsOK(ecode7)) { - SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildBiasAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicSpan_setVal" "', argument " "3"" of type '" "double""'"); } - arg7 = static_cast< iDynTree::LinkIndex >(val7); - ((iDynTree::IJoint const *)arg1)->computeChildBiasAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,*arg5,arg6,arg7); - _out = (mxArray*)0; + temp3 = static_cast< double >(val3); + arg3 = &temp3; + result = (bool)(arg1)->setVal(arg2,(iDynTree::Span< double,-1 >::element_type const &)*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42730,71 +40371,31 @@ int _wrap_IJoint_computeChildBiasAcc(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_IJoint_computeJointTorque(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - iDynTree::Wrench *arg3 = 0 ; - iDynTree::LinkIndex arg4 ; - iDynTree::LinkIndex arg5 ; - iDynTree::VectorDynSize *arg6 = 0 ; +int _wrap_DynamicSpan_at(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - ptrdiff_t val4 ; - int ecode4 = 0 ; - ptrdiff_t val5 ; - int ecode5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 >::element_type *result = 0 ; - if (!SWIG_check_num_args("IJoint_computeJointTorque",argc,6,6,0)) { + if (!SWIG_check_num_args("DynamicSpan_at",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeJointTorque" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeJointTorque" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeJointTorque" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_at" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg3 = reinterpret_cast< iDynTree::Wrench * >(argp3); - ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_computeJointTorque" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); - } - arg4 = static_cast< iDynTree::LinkIndex >(val4); - ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_computeJointTorque" "', argument " "5"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_at" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); } - arg5 = static_cast< iDynTree::LinkIndex >(val5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeJointTorque" "', argument " "6"" of type '" "iDynTree::VectorDynSize &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "6"" of type '" "iDynTree::VectorDynSize &""'"); - } - arg6 = reinterpret_cast< iDynTree::VectorDynSize * >(argp6); - ((iDynTree::IJoint const *)arg1)->computeJointTorque((iDynTree::VectorDynSize const &)*arg2,(iDynTree::Wrench const &)*arg3,arg4,arg5,*arg6); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->at(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42802,33 +40403,31 @@ int _wrap_IJoint_computeJointTorque(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_IJoint_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - iDynTree::JointIndex *arg2 = 0 ; +int _wrap_DynamicSpan_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; + iDynTree::Span< double,-1 >::index_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::Span< double,-1 >::element_type *result = 0 ; - if (!SWIG_check_num_args("IJoint_setIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("DynamicSpan_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setIndex" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_paren" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg2 = reinterpret_cast< iDynTree::JointIndex * >(argp2); - (arg1)->setIndex(*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicSpan_paren" "', argument " "2"" of type '" "iDynTree::Span< double,-1 >::index_type""'"); + } + arg2 = static_cast< iDynTree::Span< double,-1 >::index_type >(val2); + result = (iDynTree::Span< double,-1 >::element_type *) &((iDynTree::Span< double,-1 > const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42836,23 +40435,23 @@ int _wrap_IJoint_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_IJoint_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_DynamicSpan_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointIndex result; + SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,false > > result; - if (!SWIG_check_num_args("IJoint_getIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicSpan_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getIndex" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_begin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = ((iDynTree::IJoint const *)arg1)->getIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->begin(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::iterator(static_cast< const iDynTree::Span< double,-1 >::iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42860,30 +40459,23 @@ int _wrap_IJoint_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_IJoint_setPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; +int _wrap_DynamicSpan_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,false > > result; - if (!SWIG_check_num_args("IJoint_setPosCoordsOffset",argc,2,2,0)) { + if (!SWIG_check_num_args("DynamicSpan_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setPosCoordsOffset" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_end" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setPosCoordsOffset" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - (arg1)->setPosCoordsOffset(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->end(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::iterator(static_cast< const iDynTree::Span< double,-1 >::iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42891,23 +40483,23 @@ int _wrap_IJoint_setPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_IJoint_getPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_DynamicSpan_cbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,true > > result; - if (!SWIG_check_num_args("IJoint_getPosCoordsOffset",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicSpan_cbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getPosCoordsOffset" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_cbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = ((iDynTree::IJoint const *)arg1)->getPosCoordsOffset(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->cbegin(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_iterator(static_cast< const iDynTree::Span< double,-1 >::const_iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42915,30 +40507,23 @@ int _wrap_IJoint_getPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_IJoint_setDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; +int _wrap_DynamicSpan_cend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + SwigValueWrapper< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,true > > result; - if (!SWIG_check_num_args("IJoint_setDOFsOffset",argc,2,2,0)) { + if (!SWIG_check_num_args("DynamicSpan_cend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setDOFsOffset" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_cend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setDOFsOffset" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - (arg1)->setDOFsOffset(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->cend(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_iterator(static_cast< const iDynTree::Span< double,-1 >::const_iterator& >(result))), SWIGTYPE_p_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42946,23 +40531,23 @@ int _wrap_IJoint_setDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_IJoint_getDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_DynamicSpan_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + iDynTree::Span< double,-1 >::reverse_iterator result; - if (!SWIG_check_num_args("IJoint_getDOFsOffset",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicSpan_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getDOFsOffset" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_rbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = ((iDynTree::IJoint const *)arg1)->getDOFsOffset(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->rbegin(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42970,23 +40555,23 @@ int _wrap_IJoint_getDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_IJoint_hasPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_DynamicSpan_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::Span< double,-1 >::reverse_iterator result; - if (!SWIG_check_num_args("IJoint_hasPosLimits",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicSpan_rend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_hasPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_rend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (bool)((iDynTree::IJoint const *)arg1)->hasPosLimits(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->rend(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -42994,31 +40579,23 @@ int _wrap_IJoint_hasPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_IJoint_enablePosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - bool arg2 ; +int _wrap_DynamicSpan_crbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - bool val2 ; - int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::Span< double,-1 >::const_reverse_iterator result; - if (!SWIG_check_num_args("IJoint_enablePosLimits",argc,2,2,0)) { + if (!SWIG_check_num_args("DynamicSpan_crbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_enablePosLimits" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_crbegin" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_bool(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_enablePosLimits" "', argument " "2"" of type '" "bool""'"); - } - arg2 = static_cast< bool >(val2); - result = (bool)(arg1)->enablePosLimits(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->crbegin(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::const_reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43026,53 +40603,23 @@ int _wrap_IJoint_enablePosLimits(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_IJoint_getPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; - double *arg3 = 0 ; - double *arg4 = 0 ; +int _wrap_DynamicSpan_crend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Span< double,-1 > *arg1 = (iDynTree::Span< double,-1 > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; - bool result; + iDynTree::Span< double,-1 >::const_reverse_iterator result; - if (!SWIG_check_num_args("IJoint_getPosLimits",argc,4,4,0)) { + if (!SWIG_check_num_args("DynamicSpan_crend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SpanT_double__1_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getPosLimits" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_getPosLimits" "', argument " "3"" of type '" "double &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getPosLimits" "', argument " "3"" of type '" "double &""'"); - } - arg3 = reinterpret_cast< double * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_getPosLimits" "', argument " "4"" of type '" "double &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getPosLimits" "', argument " "4"" of type '" "double &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicSpan_crend" "', argument " "1"" of type '" "iDynTree::Span< double,-1 > const *""'"); } - arg4 = reinterpret_cast< double * >(argp4); - result = (bool)((iDynTree::IJoint const *)arg1)->getPosLimits(arg2,*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Span< double,-1 > * >(argp1); + result = ((iDynTree::Span< double,-1 > const *)arg1)->crend(); + _out = SWIG_NewPointerObj((new iDynTree::Span< double,-1 >::const_reverse_iterator(static_cast< const iDynTree::Span< double,-1 >::const_reverse_iterator& >(result))), SWIGTYPE_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43080,31 +40627,16 @@ int _wrap_IJoint_getPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_IJoint_getMinPosLimit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_new_DynamicMatrixView__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - double result; + iDynTree::MatrixView< double > *result = 0 ; - if (!SWIG_check_num_args("IJoint_getMinPosLimit",argc,2,2,0)) { + if (!SWIG_check_num_args("new_DynamicMatrixView",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMinPosLimit" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMinPosLimit" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (double)((iDynTree::IJoint const *)arg1)->getMinPosLimit(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + (void)argv; + result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43112,31 +40644,26 @@ int _wrap_IJoint_getMinPosLimit(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_IJoint_getMaxPosLimit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; - void *argp1 = 0 ; +int _wrap_new_DynamicMatrixView__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - double result; + iDynTree::MatrixView< double > *result = 0 ; - if (!SWIG_check_num_args("IJoint_getMaxPosLimit",argc,2,2,0)) { + if (!SWIG_check_num_args("new_DynamicMatrixView",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMaxPosLimit" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const &""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMaxPosLimit" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (double)((iDynTree::IJoint const *)arg1)->getMaxPosLimit(arg2); - _out = SWIG_From_double(static_cast< double >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const &""'"); + } + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >((iDynTree::MatrixView< double > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43144,53 +40671,50 @@ int _wrap_IJoint_getMaxPosLimit(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_IJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - size_t arg2 ; - double *arg3 = 0 ; - double *arg4 = 0 ; +int _wrap_new_DynamicMatrixView__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double >::pointer arg1 = (iDynTree::MatrixView< double >::pointer) 0 ; + iDynTree::MatrixView< double >::index_type arg2 ; + iDynTree::MatrixView< double >::index_type arg3 ; + iDynTree::MatrixStorageOrdering *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + int val4 ; + int ecode4 ; + iDynTree::MatrixStorageOrdering temp4 ; mxArray * _out; - bool result; + iDynTree::MatrixView< double > *result = 0 ; - if (!SWIG_check_num_args("IJoint_setPosLimits",argc,4,4,0)) { + if (!SWIG_check_num_args("new_DynamicMatrixView",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double >::pointer""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::MatrixView< double >::pointer >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setPosLimits" "', argument " "2"" of type '" "size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicMatrixView" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); } - arg2 = static_cast< size_t >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_setPosLimits" "', argument " "3"" of type '" "double &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setPosLimits" "', argument " "3"" of type '" "double &""'"); - } - arg3 = reinterpret_cast< double * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_setPosLimits" "', argument " "4"" of type '" "double &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setPosLimits" "', argument " "4"" of type '" "double &""'"); + arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_DynamicMatrixView" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); + ecode4 = SWIG_AsVal_int (argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "new_DynamicMatrixView" "', argument " "4"" of type '" "iDynTree::MatrixStorageOrdering const &""'"); + } else { + temp4 = static_cast< iDynTree::MatrixStorageOrdering >(val4); + arg4 = &temp4; } - arg4 = reinterpret_cast< double * >(argp4); - result = (bool)(arg1)->setPosLimits(arg2,*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(arg1,arg2,arg3,(iDynTree::MatrixStorageOrdering const &)*arg4); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43198,257 +40722,39 @@ int _wrap_IJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_IJoint_isRevoluteJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; +int _wrap_new_DynamicMatrixView__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double >::pointer arg1 = (iDynTree::MatrixView< double >::pointer) 0 ; + iDynTree::MatrixView< double >::index_type arg2 ; + iDynTree::MatrixView< double >::index_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - bool result; + iDynTree::MatrixView< double > *result = 0 ; - if (!SWIG_check_num_args("IJoint_isRevoluteJoint",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DynamicMatrixView",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_double, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isRevoluteJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double >::pointer""'"); } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (bool)iDynTree_IJoint_isRevoluteJoint((iDynTree::IJoint const *)arg1); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_IJoint_isFixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("IJoint_isFixedJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isFixedJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (bool)iDynTree_IJoint_isFixedJoint((iDynTree::IJoint const *)arg1); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_IJoint_isPrismaticJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("IJoint_isPrismaticJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isPrismaticJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (bool)iDynTree_IJoint_isPrismaticJoint((iDynTree::IJoint const *)arg1); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_IJoint_asRevoluteJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::RevoluteJoint *result = 0 ; - - if (!SWIG_check_num_args("IJoint_asRevoluteJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asRevoluteJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (iDynTree::RevoluteJoint *)iDynTree_IJoint_asRevoluteJoint(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_IJoint_asFixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::FixedJoint *result = 0 ; - - if (!SWIG_check_num_args("IJoint_asFixedJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asFixedJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (iDynTree::FixedJoint *)iDynTree_IJoint_asFixedJoint(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_IJoint_asPrismaticJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::PrismaticJoint *result = 0 ; - - if (!SWIG_check_num_args("IJoint_asPrismaticJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asPrismaticJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); - result = (iDynTree::PrismaticJoint *)iDynTree_IJoint_asPrismaticJoint(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FixedJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::FixedJoint *result = 0 ; - - if (!SWIG_check_num_args("new_FixedJoint",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FixedJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkIndex arg1 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Transform *arg3 = 0 ; - ptrdiff_t val1 ; - int ecode1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; - mxArray * _out; - iDynTree::FixedJoint *result = 0 ; - - if (!SWIG_check_num_args("new_FixedJoint",argc,3,3,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_ptrdiff_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::LinkIndex""'"); - } - arg1 = static_cast< iDynTree::LinkIndex >(val1); + arg1 = reinterpret_cast< iDynTree::MatrixView< double >::pointer >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_FixedJoint" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_DynamicMatrixView" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_FixedJoint" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); - result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint(arg1,arg2,(iDynTree::Transform const &)*arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FixedJoint__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Transform *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::FixedJoint *result = 0 ; - - if (!SWIG_check_num_args("new_FixedJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); - result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint((iDynTree::Transform const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FixedJoint__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::FixedJoint *result = 0 ; - - if (!SWIG_check_num_args("new_FixedJoint",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__FixedJoint, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint const &""'"); - } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint((iDynTree::FixedJoint const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); + arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "new_DynamicMatrixView" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); + result = (iDynTree::MatrixView< double > *)new iDynTree::MatrixView< double >(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43456,80 +40762,95 @@ int _wrap_new_FixedJoint__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_FixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_DynamicMatrixView(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_FixedJoint__SWIG_0(resc,resv,argc,argv); + return _wrap_new_DynamicMatrixView__SWIG_0(resc,resv,argc,argv); } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FixedJoint__SWIG_2(resc,resv,argc,argv); + return _wrap_new_DynamicMatrixView__SWIG_1(resc,resv,argc,argv); } } - if (argc == 1) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FixedJoint, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FixedJoint__SWIG_3(resc,resv,argc,argv); + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_DynamicMatrixView__SWIG_3(resc,resv,argc,argv); + } + } } } - if (argc == 3) { + if (argc == 4) { int _v; - { - int res = SWIG_AsVal_ptrdiff_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_double, 0); + _v = SWIG_CheckState(res); if (_v) { { int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_FixedJoint__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_int(argv[3], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_DynamicMatrixView__SWIG_2(resc,resv,argc,argv); + } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FixedJoint'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DynamicMatrixView'." " Possible C/C++ prototypes are:\n" - " iDynTree::FixedJoint::FixedJoint()\n" - " iDynTree::FixedJoint::FixedJoint(iDynTree::LinkIndex const,iDynTree::LinkIndex const,iDynTree::Transform const &)\n" - " iDynTree::FixedJoint::FixedJoint(iDynTree::Transform const &)\n" - " iDynTree::FixedJoint::FixedJoint(iDynTree::FixedJoint const &)\n"); + " iDynTree::MatrixView< double >::MatrixView()\n" + " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double > const &)\n" + " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double >::pointer,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixStorageOrdering const &)\n" + " iDynTree::MatrixView< double >::MatrixView(iDynTree::MatrixView< double >::pointer,iDynTree::MatrixView< double >::index_type,iDynTree::MatrixView< double >::index_type)\n"); return 1; } -int _wrap_delete_FixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; +int _wrap_DynamicMatrixView_storageOrder(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::MatrixStorageOrdering *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_FixedJoint",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicMatrixView_storageOrder",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_storageOrder" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + result = (iDynTree::MatrixStorageOrdering *) &((iDynTree::MatrixView< double > const *)arg1)->storageOrder(); + _out = SWIG_From_int(static_cast< int >(*result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43537,23 +40858,39 @@ int _wrap_delete_FixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_FixedJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; +int _wrap_DynamicMatrixView_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; + iDynTree::MatrixView< double >::index_type arg2 ; + iDynTree::MatrixView< double >::index_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::IJoint *result = 0 ; + iDynTree::MatrixView< double >::element_type *result = 0 ; - if (!SWIG_check_num_args("FixedJoint_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicMatrixView_paren",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_clone" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_paren" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = (iDynTree::IJoint *)((iDynTree::FixedJoint const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicMatrixView_paren" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicMatrixView_paren" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); + result = (iDynTree::MatrixView< double >::element_type *) &((iDynTree::MatrixView< double > const *)arg1)->operator ()(arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_double, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43561,23 +40898,23 @@ int _wrap_FixedJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_FixedJoint_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; +int _wrap_DynamicMatrixView_rows(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - unsigned int result; + iDynTree::MatrixView< double >::index_type result; - if (!SWIG_check_num_args("FixedJoint_getNrOfPosCoords",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicMatrixView_rows",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_rows" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = (unsigned int)((iDynTree::FixedJoint const *)arg1)->getNrOfPosCoords(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + result = ((iDynTree::MatrixView< double > const *)arg1)->rows(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43585,23 +40922,23 @@ int _wrap_FixedJoint_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_FixedJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; +int _wrap_DynamicMatrixView_cols(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - unsigned int result; + iDynTree::MatrixView< double >::index_type result; - if (!SWIG_check_num_args("FixedJoint_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("DynamicMatrixView_cols",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_cols" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = (unsigned int)((iDynTree::FixedJoint const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + result = ((iDynTree::MatrixView< double > const *)arg1)->cols(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43609,38 +40946,55 @@ int _wrap_FixedJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_FixedJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::LinkIndex arg3 ; +int _wrap_DynamicMatrixView_block(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; + iDynTree::MatrixView< double >::index_type arg2 ; + iDynTree::MatrixView< double >::index_type arg3 ; + iDynTree::MatrixView< double >::index_type arg4 ; + iDynTree::MatrixView< double >::index_type arg5 ; void *argp1 = 0 ; int res1 = 0 ; ptrdiff_t val2 ; int ecode2 = 0 ; ptrdiff_t val3 ; int ecode3 = 0 ; + ptrdiff_t val4 ; + int ecode4 = 0 ; + ptrdiff_t val5 ; + int ecode5 = 0 ; mxArray * _out; + iDynTree::MatrixView< double > result; - if (!SWIG_check_num_args("FixedJoint_setAttachedLinks",argc,3,3,0)) { + if (!SWIG_check_num_args("DynamicMatrixView_block",argc,5,5,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setAttachedLinks" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DynamicMatrixView_block" "', argument " "1"" of type '" "iDynTree::MatrixView< double > const *""'"); } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_setAttachedLinks" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DynamicMatrixView_block" "', argument " "2"" of type '" "iDynTree::MatrixView< double >::index_type""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = static_cast< iDynTree::MatrixView< double >::index_type >(val2); ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "FixedJoint_setAttachedLinks" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "DynamicMatrixView_block" "', argument " "3"" of type '" "iDynTree::MatrixView< double >::index_type""'"); } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - (arg1)->setAttachedLinks(arg2,arg3); - _out = (mxArray*)0; + arg3 = static_cast< iDynTree::MatrixView< double >::index_type >(val3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "DynamicMatrixView_block" "', argument " "4"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg4 = static_cast< iDynTree::MatrixView< double >::index_type >(val4); + ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "DynamicMatrixView_block" "', argument " "5"" of type '" "iDynTree::MatrixView< double >::index_type""'"); + } + arg5 = static_cast< iDynTree::MatrixView< double >::index_type >(val5); + result = ((iDynTree::MatrixView< double > const *)arg1)->block(arg2,arg3,arg4,arg5); + _out = SWIG_NewPointerObj((new iDynTree::MatrixView< double >(static_cast< const iDynTree::MatrixView< double >& >(result))), SWIGTYPE_p_iDynTree__MatrixViewT_double_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -43648,32 +41002,25 @@ int _wrap_FixedJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_FixedJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_delete_DynamicMatrixView(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MatrixView< double > *arg1 = (iDynTree::MatrixView< double > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("FixedJoint_setRestTransform",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_DynamicMatrixView",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MatrixViewT_double_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setRestTransform" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); - } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FixedJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DynamicMatrixView" "', argument " "1"" of type '" "iDynTree::MatrixView< double > *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FixedJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + arg1 = reinterpret_cast< iDynTree::MatrixView< double > * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - (arg1)->setRestTransform((iDynTree::Transform const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -43682,64 +41029,5002 @@ int _wrap_FixedJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_FixedJoint_getFirstAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::LinkIndex result; - - if (!SWIG_check_num_args("FixedJoint_getFirstAttachedLink",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getFirstAttachedLink" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); - } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = ((iDynTree::FixedJoint const *)arg1)->getFirstAttachedLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); - if (_out) --resc, *resv++ = _out; +SWIGINTERN int _wrap_LINK_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::LINK_INVALID_INDEX)); return 0; -fail: - return 1; } -int _wrap_FixedJoint_getSecondAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::LinkIndex result; - - if (!SWIG_check_num_args("FixedJoint_getSecondAttachedLink",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getSecondAttachedLink" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); +SWIGINTERN int _wrap_LINK_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + ptrdiff_t val; + int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); + if (!SWIG_IsOK(res)) { + SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::LINK_INVALID_INDEX""' of type '""iDynTree::LinkIndex""'"); + } + iDynTree::LINK_INVALID_INDEX = static_cast< iDynTree::LinkIndex >(val); } - arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - result = ((iDynTree::FixedJoint const *)arg1)->getSecondAttachedLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); - if (_out) --resc, *resv++ = _out; return 0; fail: return 1; } -int _wrap_FixedJoint_getRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::LinkIndex arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; +SWIGINTERN int _wrap_LINK_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::LINK_INVALID_NAME)); + return 0; +} + + +SWIGINTERN int _wrap_LINK_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[0], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::LINK_INVALID_NAME""' of type '""std::string""'"); + } + iDynTree::LINK_INVALID_NAME = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_JOINT_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::JOINT_INVALID_INDEX)); + return 0; +} + + +SWIGINTERN int _wrap_JOINT_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + ptrdiff_t val; + int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); + if (!SWIG_IsOK(res)) { + SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::JOINT_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); + } + iDynTree::JOINT_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_JOINT_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::JOINT_INVALID_NAME)); + return 0; +} + + +SWIGINTERN int _wrap_JOINT_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[0], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::JOINT_INVALID_NAME""' of type '""std::string""'"); + } + iDynTree::JOINT_INVALID_NAME = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_DOF_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::DOF_INVALID_INDEX)); + return 0; +} + + +SWIGINTERN int _wrap_DOF_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + ptrdiff_t val; + int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); + if (!SWIG_IsOK(res)) { + SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::DOF_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); + } + iDynTree::DOF_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_DOF_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::DOF_INVALID_NAME)); + return 0; +} + + +SWIGINTERN int _wrap_DOF_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[0], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::DOF_INVALID_NAME""' of type '""std::string""'"); + } + iDynTree::DOF_INVALID_NAME = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_FRAME_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::FRAME_INVALID_INDEX)); + return 0; +} + + +SWIGINTERN int _wrap_FRAME_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + ptrdiff_t val; + int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); + if (!SWIG_IsOK(res)) { + SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::FRAME_INVALID_INDEX""' of type '""std::ptrdiff_t""'"); + } + iDynTree::FRAME_INVALID_INDEX = static_cast< std::ptrdiff_t >(val); + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_FRAME_INVALID_NAME_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_std_string(static_cast< std::string >(iDynTree::FRAME_INVALID_NAME)); + return 0; +} + + +SWIGINTERN int _wrap_FRAME_INVALID_NAME_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[0], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in variable '""iDynTree::FRAME_INVALID_NAME""' of type '""std::string""'"); + } + iDynTree::FRAME_INVALID_NAME = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + return 0; +fail: + return 1; +} + + +SWIGINTERN int _wrap_TRAVERSAL_INVALID_INDEX_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(iDynTree::TRAVERSAL_INVALID_INDEX)); + return 0; +} + + +SWIGINTERN int _wrap_TRAVERSAL_INVALID_INDEX_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + { + ptrdiff_t val; + int res = SWIG_AsVal_ptrdiff_t(argv[0], &val); + if (!SWIG_IsOK(res)) { + SWIG_exception_fail(SWIG_ArgError(res), "in variable '""iDynTree::TRAVERSAL_INVALID_INDEX""' of type '""iDynTree::TraversalIndex""'"); + } + iDynTree::TRAVERSAL_INVALID_INDEX = static_cast< iDynTree::TraversalIndex >(val); + } + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkPositions__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkPositions *result = 0 ; + + if (!SWIG_check_num_args("new_LinkPositions",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkPositions" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkPositions__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkPositions *result = 0 ; + + if (!SWIG_check_num_args("new_LinkPositions",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkPositions__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkPositions *result = 0 ; + + if (!SWIG_check_num_args("new_LinkPositions",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkPositions" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkPositions" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkPositions *)new iDynTree::LinkPositions((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkPositions, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkPositions__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkPositions__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkPositions__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkPositions'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkPositions::LinkPositions(std::size_t)\n" + " iDynTree::LinkPositions::LinkPositions()\n" + " iDynTree::LinkPositions::LinkPositions(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkPositions_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkPositions_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_resize" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkPositions_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_resize" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkPositions_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkPositions_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkPositions_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkPositions::resize(std::size_t)\n" + " iDynTree::LinkPositions::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkPositions_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkPositions_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkPositions const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("LinkPositions_getNrOfLinks",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + result = ((iDynTree::LinkPositions const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Transform *result = 0 ; + + if (!SWIG_check_num_args("LinkPositions_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_paren" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Transform *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Transform *result = 0 ; + + if (!SWIG_check_num_args("LinkPositions_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_paren" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkPositions_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Transform *) &((iDynTree::LinkPositions const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkPositions_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkPositions_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkPositions_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkPositions_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkPositions::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkPositions::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_LinkPositions_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("LinkPositions_toString",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkPositions_toString" "', argument " "1"" of type '" "iDynTree::LinkPositions const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkPositions_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkPositions_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::LinkPositions const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_LinkPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkPositions *arg1 = (iDynTree::LinkPositions *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkPositions",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkPositions, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkPositions" "', argument " "1"" of type '" "iDynTree::LinkPositions *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkPositions * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkWrenches__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkWrenches *result = 0 ; + + if (!SWIG_check_num_args("new_LinkWrenches",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkWrenches__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkWrenches *result = 0 ; + + if (!SWIG_check_num_args("new_LinkWrenches",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkWrenches__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkWrenches *result = 0 ; + + if (!SWIG_check_num_args("new_LinkWrenches",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkWrenches *)new iDynTree::LinkWrenches((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkWrenches__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkWrenches__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkWrenches__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkWrenches'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkWrenches::LinkWrenches(std::size_t)\n" + " iDynTree::LinkWrenches::LinkWrenches()\n" + " iDynTree::LinkWrenches::LinkWrenches(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkWrenches_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkWrenches_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkWrenches_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkWrenches_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkWrenches_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkWrenches_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkWrenches::resize(std::size_t)\n" + " iDynTree::LinkWrenches::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkWrenches_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkWrenches_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkWrenches const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("LinkWrenches_getNrOfLinks",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + result = ((iDynTree::LinkWrenches const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Wrench *result = 0 ; + + if (!SWIG_check_num_args("LinkWrenches_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_paren" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Wrench *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Wrench *result = 0 ; + + if (!SWIG_check_num_args("LinkWrenches_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_paren" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkWrenches_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Wrench *) &((iDynTree::LinkWrenches const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkWrenches_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkWrenches_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkWrenches_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkWrenches::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkWrenches::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_LinkWrenches_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("LinkWrenches_toString",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_toString" "', argument " "1"" of type '" "iDynTree::LinkWrenches const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::LinkWrenches const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkWrenches_zero(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkWrenches_zero",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkWrenches_zero" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + (arg1)->zero(); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_LinkWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkWrenches *arg1 = (iDynTree::LinkWrenches *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkWrenches",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkWrenches, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkWrenches" "', argument " "1"" of type '" "iDynTree::LinkWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkWrenches * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkInertias__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkInertias",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkInertias" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkInertias__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkInertias",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkInertias__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkInertias",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkInertias *)new iDynTree::LinkInertias((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkInertias__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkInertias__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkInertias__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkInertias'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkInertias::LinkInertias(std::size_t)\n" + " iDynTree::LinkInertias::LinkInertias()\n" + " iDynTree::LinkInertias::LinkInertias(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkInertias_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkInertias_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkInertias_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkInertias_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkInertias_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkInertias_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkInertias_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkInertias_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkInertias::resize(std::size_t)\n" + " iDynTree::LinkInertias::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkInertias_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkInertias_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkInertias const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkInertias const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkInertias_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia *result = 0 ; + + if (!SWIG_check_num_args("LinkInertias_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::SpatialInertia *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkInertias_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia *result = 0 ; + + if (!SWIG_check_num_args("LinkInertias_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkInertias const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::SpatialInertia *) &((iDynTree::LinkInertias const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkInertias_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkInertias_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkInertias_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkInertias_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkInertias::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkInertias::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_delete_LinkInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkInertias *arg1 = (iDynTree::LinkInertias *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkInertias",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkInertias, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkInertias" "', argument " "1"" of type '" "iDynTree::LinkInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkInertias * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkArticulatedBodyInertias__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkArticulatedBodyInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkArticulatedBodyInertias__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkArticulatedBodyInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkArticulatedBodyInertias__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkArticulatedBodyInertias *result = 0 ; + + if (!SWIG_check_num_args("new_LinkArticulatedBodyInertias",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkArticulatedBodyInertias *)new iDynTree::LinkArticulatedBodyInertias((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkArticulatedBodyInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkArticulatedBodyInertias__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkArticulatedBodyInertias__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkArticulatedBodyInertias__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkArticulatedBodyInertias'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias(std::size_t)\n" + " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias()\n" + " iDynTree::LinkArticulatedBodyInertias::LinkArticulatedBodyInertias(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkArticulatedBodyInertias_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkArticulatedBodyInertias_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkArticulatedBodyInertias_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkArticulatedBodyInertias_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkArticulatedBodyInertias_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkArticulatedBodyInertias_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkArticulatedBodyInertias::resize(std::size_t)\n" + " iDynTree::LinkArticulatedBodyInertias::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkArticulatedBodyInertias_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkArticulatedBodyInertias_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkArticulatedBodyInertias const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::ArticulatedBodyInertia *result = 0 ; + + if (!SWIG_check_num_args("LinkArticulatedBodyInertias_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::ArticulatedBodyInertia *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::ArticulatedBodyInertia *result = 0 ; + + if (!SWIG_check_num_args("LinkArticulatedBodyInertias_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkArticulatedBodyInertias_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::ArticulatedBodyInertia *) &((iDynTree::LinkArticulatedBodyInertias const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkArticulatedBodyInertias_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkArticulatedBodyInertias_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkArticulatedBodyInertias_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkArticulatedBodyInertias_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkArticulatedBodyInertias::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkArticulatedBodyInertias::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_delete_LinkArticulatedBodyInertias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkArticulatedBodyInertias *arg1 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkArticulatedBodyInertias",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkArticulatedBodyInertias" "', argument " "1"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkVelArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkVelArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkVelArray",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkVelArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkVelArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkVelArray",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkVelArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkVelArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkVelArray",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkVelArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkVelArray *)new iDynTree::LinkVelArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkVelArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkVelArray__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkVelArray__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkVelArray__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkVelArray'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkVelArray::LinkVelArray(std::size_t)\n" + " iDynTree::LinkVelArray::LinkVelArray()\n" + " iDynTree::LinkVelArray::LinkVelArray(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkVelArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkVelArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_resize" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkVelArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_resize" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkVelArray_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkVelArray_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkVelArray_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkVelArray::resize(std::size_t)\n" + " iDynTree::LinkVelArray::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkVelArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkVelArray_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkVelArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("LinkVelArray_getNrOfLinks",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + result = ((iDynTree::LinkVelArray const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Twist *result = 0 ; + + if (!SWIG_check_num_args("LinkVelArray_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_paren" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Twist *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::Twist *result = 0 ; + + if (!SWIG_check_num_args("LinkVelArray_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_paren" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkVelArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::Twist *) &((iDynTree::LinkVelArray const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkVelArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkVelArray_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkVelArray_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkVelArray_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkVelArray::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkVelArray::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_LinkVelArray_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("LinkVelArray_toString",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkVelArray_toString" "', argument " "1"" of type '" "iDynTree::LinkVelArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkVelArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkVelArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::LinkVelArray const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_LinkVelArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkVelArray *arg1 = (iDynTree::LinkVelArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkVelArray",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkVelArray, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkVelArray" "', argument " "1"" of type '" "iDynTree::LinkVelArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkVelArray * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkAccArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::LinkAccArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkAccArray",argc,1,1,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkAccArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::LinkAccArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkAccArray",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkAccArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkAccArray *result = 0 ; + + if (!SWIG_check_num_args("new_LinkAccArray",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkAccArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkAccArray *)new iDynTree::LinkAccArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinkAccArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkAccArray__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinkAccArray__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinkAccArray__SWIG_0(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkAccArray'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkAccArray::LinkAccArray(std::size_t)\n" + " iDynTree::LinkAccArray::LinkAccArray()\n" + " iDynTree::LinkAccArray::LinkAccArray(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkAccArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkAccArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_resize" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkAccArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_resize" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkAccArray_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkAccArray_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkAccArray_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkAccArray::resize(std::size_t)\n" + " iDynTree::LinkAccArray::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_LinkAccArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("LinkAccArray_isConsistent",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkAccArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::SpatialAcc *result = 0 ; + + if (!SWIG_check_num_args("LinkAccArray_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_paren" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::SpatialAcc *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::SpatialAcc *result = 0 ; + + if (!SWIG_check_num_args("LinkAccArray_paren",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_paren" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkAccArray_paren" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::SpatialAcc *) &((iDynTree::LinkAccArray const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkAccArray_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkAccArray_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkAccArray_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::LinkAccArray::operator ()(iDynTree::LinkIndex const)\n" + " iDynTree::LinkAccArray::operator ()(iDynTree::LinkIndex const) const\n"); + return 1; +} + + +int _wrap_LinkAccArray_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("LinkAccArray_getNrOfLinks",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + result = ((iDynTree::LinkAccArray const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkAccArray_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("LinkAccArray_toString",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkAccArray_toString" "', argument " "1"" of type '" "iDynTree::LinkAccArray const *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkAccArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkAccArray_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::LinkAccArray const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_LinkAccArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkAccArray *arg1 = (iDynTree::LinkAccArray *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkAccArray",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkAccArray, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkAccArray" "', argument " "1"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkAccArray * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::Link *result = 0 ; + + if (!SWIG_check_num_args("new_Link",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::Link *)new iDynTree::Link(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_inertia__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia *result = 0 ; + + if (!SWIG_check_num_args("Link_inertia",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_inertia" "', argument " "1"" of type '" "iDynTree::Link *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + result = (iDynTree::SpatialInertia *) &(arg1)->inertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_inertia__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia *result = 0 ; + + if (!SWIG_check_num_args("Link_inertia",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_inertia" "', argument " "1"" of type '" "iDynTree::Link const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + result = (iDynTree::SpatialInertia *) &((iDynTree::Link const *)arg1)->inertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_inertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Link, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Link_inertia__SWIG_0(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Link, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Link_inertia__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Link_inertia'." + " Possible C/C++ prototypes are:\n" + " iDynTree::Link::inertia()\n" + " iDynTree::Link::inertia() const\n"); + return 1; +} + + +int _wrap_Link_setInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + iDynTree::SpatialInertia *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("Link_setInertia",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_setInertia" "', argument " "1"" of type '" "iDynTree::Link *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialInertia, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Link_setInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Link_setInertia" "', argument " "2"" of type '" "iDynTree::SpatialInertia &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialInertia * >(argp2); + (arg1)->setInertia(*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_getInertia(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SpatialInertia *result = 0 ; + + if (!SWIG_check_num_args("Link_getInertia",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_getInertia" "', argument " "1"" of type '" "iDynTree::Link const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + result = (iDynTree::SpatialInertia *) &((iDynTree::Link const *)arg1)->getInertia(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialInertia, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("Link_setIndex",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_setIndex" "', argument " "1"" of type '" "iDynTree::Link *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Link_setIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Link_setIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex &""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkIndex * >(argp2); + (arg1)->setIndex(*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Link_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("Link_getIndex",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Link_getIndex" "', argument " "1"" of type '" "iDynTree::Link const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + result = ((iDynTree::Link const *)arg1)->getIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_Link(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Link *arg1 = (iDynTree::Link *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_Link",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Link, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Link" "', argument " "1"" of type '" "iDynTree::Link *""'"); + } + arg1 = reinterpret_cast< iDynTree::Link * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_IJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_IJoint",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_IJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::IJoint *result = 0 ; + + if (!SWIG_check_num_args("IJoint_clone",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_clone" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (iDynTree::IJoint *)((iDynTree::IJoint const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + unsigned int result; + + if (!SWIG_check_num_args("IJoint_getNrOfPosCoords",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (unsigned int)((iDynTree::IJoint const *)arg1)->getNrOfPosCoords(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + unsigned int result; + + if (!SWIG_check_num_args("IJoint_getNrOfDOFs",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (unsigned int)((iDynTree::IJoint const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::LinkIndex arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_setAttachedLinks",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setAttachedLinks" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setAttachedLinks" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_setAttachedLinks" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + (arg1)->setAttachedLinks(arg2,arg3); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::Transform *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_setRestTransform",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setRestTransform" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + (arg1)->setRestTransform((iDynTree::Transform const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getFirstAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("IJoint_getFirstAttachedLink",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getFirstAttachedLink" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = ((iDynTree::IJoint const *)arg1)->getFirstAttachedLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getSecondAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("IJoint_getSecondAttachedLink",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getSecondAttachedLink" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = ((iDynTree::IJoint const *)arg1)->getSecondAttachedLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::LinkIndex arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + mxArray * _out; + iDynTree::Transform result; + + if (!SWIG_check_num_args("IJoint_getRestTransform",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getRestTransform" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getRestTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getRestTransform" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + result = ((iDynTree::IJoint const *)arg1)->getRestTransform(arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::LinkIndex arg3 ; + iDynTree::LinkIndex arg4 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + ptrdiff_t val4 ; + int ecode4 = 0 ; + mxArray * _out; + iDynTree::Transform *result = 0 ; + + if (!SWIG_check_num_args("IJoint_getTransform",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getTransform" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_getTransform" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getTransform" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getTransform" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getTransform" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + } + arg4 = static_cast< iDynTree::LinkIndex >(val4); + result = (iDynTree::Transform *) &((iDynTree::IJoint const *)arg1)->getTransform((iDynTree::VectorDynSize const &)*arg2,arg3,arg4); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getTransformDerivative(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::LinkIndex arg3 ; + iDynTree::LinkIndex arg4 ; + int arg5 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + ptrdiff_t val4 ; + int ecode4 = 0 ; + int val5 ; + int ecode5 = 0 ; + mxArray * _out; + iDynTree::TransformDerivative result; + + if (!SWIG_check_num_args("IJoint_getTransformDerivative",argc,5,5,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getTransformDerivative" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_getTransformDerivative" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getTransformDerivative" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getTransformDerivative" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getTransformDerivative" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + } + arg4 = static_cast< iDynTree::LinkIndex >(val4); + ecode5 = SWIG_AsVal_int(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_getTransformDerivative" "', argument " "5"" of type '" "int""'"); + } + arg5 = static_cast< int >(val5); + result = ((iDynTree::IJoint const *)arg1)->getTransformDerivative((iDynTree::VectorDynSize const &)*arg2,arg3,arg4,arg5); + _out = SWIG_NewPointerObj((new iDynTree::TransformDerivative(static_cast< const iDynTree::TransformDerivative& >(result))), SWIGTYPE_p_iDynTree__TransformDerivative, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getMotionSubspaceVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + int arg2 ; + iDynTree::LinkIndex arg3 ; + iDynTree::LinkIndex arg4 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + ptrdiff_t val4 ; + int ecode4 = 0 ; + mxArray * _out; + iDynTree::SpatialMotionVector result; + + if (!SWIG_check_num_args("IJoint_getMotionSubspaceVector",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "2"" of type '" "int""'"); + } + arg2 = static_cast< int >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_getMotionSubspaceVector" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + } + arg4 = static_cast< iDynTree::LinkIndex >(val4); + result = ((iDynTree::IJoint const *)arg1)->getMotionSubspaceVector(arg2,arg3,arg4); + _out = SWIG_NewPointerObj((new iDynTree::SpatialMotionVector(static_cast< const iDynTree::SpatialMotionVector& >(result))), SWIGTYPE_p_iDynTree__SpatialMotionVector, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeChildPosVelAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::VectorDynSize *arg4 = 0 ; + iDynTree::LinkPositions *arg5 = 0 ; + iDynTree::LinkVelArray *arg6 = 0 ; + iDynTree::LinkAccArray *arg7 = 0 ; + iDynTree::LinkIndex arg8 ; + iDynTree::LinkIndex arg9 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; + ptrdiff_t val8 ; + int ecode8 = 0 ; + ptrdiff_t val9 ; + int ecode9 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeChildPosVelAcc",argc,9,9,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildPosVelAcc" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); + ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); + if (!SWIG_IsOK(ecode8)) { + SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); + } + arg8 = static_cast< iDynTree::LinkIndex >(val8); + ecode9 = SWIG_AsVal_ptrdiff_t(argv[8], &val9); + if (!SWIG_IsOK(ecode9)) { + SWIG_exception_fail(SWIG_ArgError(ecode9), "in method '" "IJoint_computeChildPosVelAcc" "', argument " "9"" of type '" "iDynTree::LinkIndex""'"); + } + arg9 = static_cast< iDynTree::LinkIndex >(val9); + ((iDynTree::IJoint const *)arg1)->computeChildPosVelAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5,*arg6,*arg7,arg8,arg9); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeChildVelAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::VectorDynSize *arg4 = 0 ; + iDynTree::LinkVelArray *arg5 = 0 ; + iDynTree::LinkAccArray *arg6 = 0 ; + iDynTree::LinkIndex arg7 ; + iDynTree::LinkIndex arg8 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + ptrdiff_t val7 ; + int ecode7 = 0 ; + ptrdiff_t val8 ; + int ecode8 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeChildVelAcc",argc,8,8,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildVelAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildVelAcc" "', argument " "5"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "5"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkVelArray * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildVelAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVelAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); + ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); + if (!SWIG_IsOK(ecode7)) { + SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildVelAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); + } + arg7 = static_cast< iDynTree::LinkIndex >(val7); + ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); + if (!SWIG_IsOK(ecode8)) { + SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildVelAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); + } + arg8 = static_cast< iDynTree::LinkIndex >(val8); + ((iDynTree::IJoint const *)arg1)->computeChildVelAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5,*arg6,arg7,arg8); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeChildVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::LinkIndex arg5 ; + iDynTree::LinkIndex arg6 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + ptrdiff_t val5 ; + int ecode5 = 0 ; + ptrdiff_t val6 ; + int ecode6 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeChildVel",argc,6,6,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildVel" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildVel" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildVel" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildVel" "', argument " "4"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildVel" "', argument " "4"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_computeChildVel" "', argument " "5"" of type '" "iDynTree::LinkIndex""'"); + } + arg5 = static_cast< iDynTree::LinkIndex >(val5); + ecode6 = SWIG_AsVal_ptrdiff_t(argv[5], &val6); + if (!SWIG_IsOK(ecode6)) { + SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "IJoint_computeChildVel" "', argument " "6"" of type '" "iDynTree::LinkIndex""'"); + } + arg6 = static_cast< iDynTree::LinkIndex >(val6); + ((iDynTree::IJoint const *)arg1)->computeChildVel((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,*arg4,arg5,arg6); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeChildAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::VectorDynSize *arg5 = 0 ; + iDynTree::LinkAccArray *arg6 = 0 ; + iDynTree::LinkIndex arg7 ; + iDynTree::LinkIndex arg8 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + ptrdiff_t val7 ; + int ecode7 = 0 ; + ptrdiff_t val8 ; + int ecode8 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeChildAcc",argc,8,8,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildAcc" "', argument " "5"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "5"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg5 = reinterpret_cast< iDynTree::VectorDynSize * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeChildAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildAcc" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); + ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); + if (!SWIG_IsOK(ecode7)) { + SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); + } + arg7 = static_cast< iDynTree::LinkIndex >(val7); + ecode8 = SWIG_AsVal_ptrdiff_t(argv[7], &val8); + if (!SWIG_IsOK(ecode8)) { + SWIG_exception_fail(SWIG_ArgError(ecode8), "in method '" "IJoint_computeChildAcc" "', argument " "8"" of type '" "iDynTree::LinkIndex""'"); + } + arg8 = static_cast< iDynTree::LinkIndex >(val8); + ((iDynTree::IJoint const *)arg1)->computeChildAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::VectorDynSize const &)*arg5,*arg6,arg7,arg8); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeChildBiasAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::LinkAccArray *arg5 = 0 ; + iDynTree::LinkIndex arg6 ; + iDynTree::LinkIndex arg7 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + ptrdiff_t val6 ; + int ecode6 = 0 ; + ptrdiff_t val7 ; + int ecode7 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeChildBiasAcc",argc,7,7,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeChildBiasAcc" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeChildBiasAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeChildBiasAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_computeChildBiasAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "IJoint_computeChildBiasAcc" "', argument " "5"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeChildBiasAcc" "', argument " "5"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); + ecode6 = SWIG_AsVal_ptrdiff_t(argv[5], &val6); + if (!SWIG_IsOK(ecode6)) { + SWIG_exception_fail(SWIG_ArgError(ecode6), "in method '" "IJoint_computeChildBiasAcc" "', argument " "6"" of type '" "iDynTree::LinkIndex""'"); + } + arg6 = static_cast< iDynTree::LinkIndex >(val6); + ecode7 = SWIG_AsVal_ptrdiff_t(argv[6], &val7); + if (!SWIG_IsOK(ecode7)) { + SWIG_exception_fail(SWIG_ArgError(ecode7), "in method '" "IJoint_computeChildBiasAcc" "', argument " "7"" of type '" "iDynTree::LinkIndex""'"); + } + arg7 = static_cast< iDynTree::LinkIndex >(val7); + ((iDynTree::IJoint const *)arg1)->computeChildBiasAcc((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,*arg5,arg6,arg7); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_computeJointTorque(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::Wrench *arg3 = 0 ; + iDynTree::LinkIndex arg4 ; + iDynTree::LinkIndex arg5 ; + iDynTree::VectorDynSize *arg6 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + ptrdiff_t val4 ; + int ecode4 = 0 ; + ptrdiff_t val5 ; + int ecode5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_computeJointTorque",argc,6,6,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_computeJointTorque" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_computeJointTorque" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_computeJointTorque" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Wrench * >(argp3); + ecode4 = SWIG_AsVal_ptrdiff_t(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "IJoint_computeJointTorque" "', argument " "4"" of type '" "iDynTree::LinkIndex""'"); + } + arg4 = static_cast< iDynTree::LinkIndex >(val4); + ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "IJoint_computeJointTorque" "', argument " "5"" of type '" "iDynTree::LinkIndex""'"); + } + arg5 = static_cast< iDynTree::LinkIndex >(val5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "IJoint_computeJointTorque" "', argument " "6"" of type '" "iDynTree::VectorDynSize &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_computeJointTorque" "', argument " "6"" of type '" "iDynTree::VectorDynSize &""'"); + } + arg6 = reinterpret_cast< iDynTree::VectorDynSize * >(argp6); + ((iDynTree::IJoint const *)arg1)->computeJointTorque((iDynTree::VectorDynSize const &)*arg2,(iDynTree::Wrench const &)*arg3,arg4,arg5,*arg6); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::JointIndex *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_setIndex",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setIndex" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "IJoint_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); + } + arg2 = reinterpret_cast< iDynTree::JointIndex * >(argp2); + (arg1)->setIndex(*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointIndex result; + + if (!SWIG_check_num_args("IJoint_getIndex",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getIndex" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = ((iDynTree::IJoint const *)arg1)->getIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_setPosCoordsOffset",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setPosCoordsOffset" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setPosCoordsOffset" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + (arg1)->setPosCoordsOffset(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getPosCoordsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("IJoint_getPosCoordsOffset",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getPosCoordsOffset" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = ((iDynTree::IJoint const *)arg1)->getPosCoordsOffset(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("IJoint_setDOFsOffset",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setDOFsOffset" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setDOFsOffset" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + (arg1)->setDOFsOffset(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getDOFsOffset(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("IJoint_getDOFsOffset",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getDOFsOffset" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = ((iDynTree::IJoint const *)arg1)->getDOFsOffset(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_hasPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_hasPosLimits",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_hasPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (bool)((iDynTree::IJoint const *)arg1)->hasPosLimits(); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_enablePosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + bool arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + bool val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_enablePosLimits",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_enablePosLimits" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_bool(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_enablePosLimits" "', argument " "2"" of type '" "bool""'"); + } + arg2 = static_cast< bool >(val2); + result = (bool)(arg1)->enablePosLimits(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + double *arg4 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_getPosLimits",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getPosLimits" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_getPosLimits" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getPosLimits" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_getPosLimits" "', argument " "4"" of type '" "double &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_getPosLimits" "', argument " "4"" of type '" "double &""'"); + } + arg4 = reinterpret_cast< double * >(argp4); + result = (bool)((iDynTree::IJoint const *)arg1)->getPosLimits(arg2,*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getMinPosLimit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("IJoint_getMinPosLimit",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMinPosLimit" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMinPosLimit" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::IJoint const *)arg1)->getMinPosLimit(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getMaxPosLimit(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("IJoint_getMaxPosLimit",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getMaxPosLimit" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getMaxPosLimit" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::IJoint const *)arg1)->getMaxPosLimit(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + double *arg4 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_setPosLimits",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setPosLimits" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setPosLimits" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_setPosLimits" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setPosLimits" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "IJoint_setPosLimits" "', argument " "4"" of type '" "double &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setPosLimits" "', argument " "4"" of type '" "double &""'"); + } + arg4 = reinterpret_cast< double * >(argp4); + result = (bool)(arg1)->setPosLimits(arg2,*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointDynamicsType result; + + if (!SWIG_check_num_args("IJoint_getJointDynamicsType",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getJointDynamicsType" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (iDynTree::JointDynamicsType)((iDynTree::IJoint const *)arg1)->getJointDynamicsType(); + _out = SWIG_From_int(static_cast< int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + iDynTree::JointDynamicsType arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_setJointDynamicsType",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setJointDynamicsType" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setJointDynamicsType" "', argument " "2"" of type '" "iDynTree::JointDynamicsType""'"); + } + arg2 = static_cast< iDynTree::JointDynamicsType >(val2); + result = (bool)(arg1)->setJointDynamicsType(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_setDamping",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setDamping" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setDamping(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_setStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_setStaticFriction",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_setStaticFriction" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_setStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "IJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "IJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setStaticFriction(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("IJoint_getDamping",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getDamping" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::IJoint const *)arg1)->getDamping(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_getStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("IJoint_getStaticFriction",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_getStaticFriction" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "IJoint_getStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::IJoint const *)arg1)->getStaticFriction(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_isRevoluteJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_isRevoluteJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isRevoluteJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (bool)iDynTree_IJoint_isRevoluteJoint((iDynTree::IJoint const *)arg1); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_isFixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_isFixedJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isFixedJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (bool)iDynTree_IJoint_isFixedJoint((iDynTree::IJoint const *)arg1); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_isPrismaticJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("IJoint_isPrismaticJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_isPrismaticJoint" "', argument " "1"" of type '" "iDynTree::IJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (bool)iDynTree_IJoint_isPrismaticJoint((iDynTree::IJoint const *)arg1); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_asRevoluteJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::RevoluteJoint *result = 0 ; + + if (!SWIG_check_num_args("IJoint_asRevoluteJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asRevoluteJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (iDynTree::RevoluteJoint *)iDynTree_IJoint_asRevoluteJoint(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_asFixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::FixedJoint *result = 0 ; + + if (!SWIG_check_num_args("IJoint_asFixedJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asFixedJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (iDynTree::FixedJoint *)iDynTree_IJoint_asFixedJoint(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_IJoint_asPrismaticJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::IJoint *arg1 = (iDynTree::IJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::PrismaticJoint *result = 0 ; + + if (!SWIG_check_num_args("IJoint_asPrismaticJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "IJoint_asPrismaticJoint" "', argument " "1"" of type '" "iDynTree::IJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::IJoint * >(argp1); + result = (iDynTree::PrismaticJoint *)iDynTree_IJoint_asPrismaticJoint(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FixedJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::FixedJoint *result = 0 ; + + if (!SWIG_check_num_args("new_FixedJoint",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FixedJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkIndex arg1 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Transform *arg3 = 0 ; + ptrdiff_t val1 ; + int ecode1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; + mxArray * _out; + iDynTree::FixedJoint *result = 0 ; + + if (!SWIG_check_num_args("new_FixedJoint",argc,3,3,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_ptrdiff_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::LinkIndex""'"); + } + arg1 = static_cast< iDynTree::LinkIndex >(val1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "new_FixedJoint" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "new_FixedJoint" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); + result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint(arg1,arg2,(iDynTree::Transform const &)*arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FixedJoint__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Transform *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::FixedJoint *result = 0 ; + + if (!SWIG_check_num_args("new_FixedJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::Transform const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Transform * >(argp1); + result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint((iDynTree::Transform const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FixedJoint__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::FixedJoint *result = 0 ; + + if (!SWIG_check_num_args("new_FixedJoint",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__FixedJoint, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint const &""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = (iDynTree::FixedJoint *)new iDynTree::FixedJoint((iDynTree::FixedJoint const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FixedJoint, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FixedJoint__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FixedJoint__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FixedJoint, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FixedJoint__SWIG_3(resc,resv,argc,argv); + } + } + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_ptrdiff_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FixedJoint__SWIG_1(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FixedJoint'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FixedJoint::FixedJoint()\n" + " iDynTree::FixedJoint::FixedJoint(iDynTree::LinkIndex const,iDynTree::LinkIndex const,iDynTree::Transform const &)\n" + " iDynTree::FixedJoint::FixedJoint(iDynTree::Transform const &)\n" + " iDynTree::FixedJoint::FixedJoint(iDynTree::FixedJoint const &)\n"); + return 1; +} + + +int _wrap_delete_FixedJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_FixedJoint",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FixedJoint" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::IJoint *result = 0 ; + + if (!SWIG_check_num_args("FixedJoint_clone",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_clone" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = (iDynTree::IJoint *)((iDynTree::FixedJoint const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + unsigned int result; + + if (!SWIG_check_num_args("FixedJoint_getNrOfPosCoords",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = (unsigned int)((iDynTree::FixedJoint const *)arg1)->getNrOfPosCoords(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + unsigned int result; + + if (!SWIG_check_num_args("FixedJoint_getNrOfDOFs",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = (unsigned int)((iDynTree::FixedJoint const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_setAttachedLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::LinkIndex arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("FixedJoint_setAttachedLinks",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setAttachedLinks" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_setAttachedLinks" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "FixedJoint_setAttachedLinks" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + (arg1)->setAttachedLinks(arg2,arg3); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_setRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + iDynTree::Transform *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("FixedJoint_setRestTransform",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setRestTransform" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FixedJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FixedJoint_setRestTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + (arg1)->setRestTransform((iDynTree::Transform const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getFirstAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("FixedJoint_getFirstAttachedLink",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getFirstAttachedLink" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = ((iDynTree::FixedJoint const *)arg1)->getFirstAttachedLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getSecondAttachedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("FixedJoint_getSecondAttachedLink",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getSecondAttachedLink" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = ((iDynTree::FixedJoint const *)arg1)->getSecondAttachedLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getRestTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::LinkIndex arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; iDynTree::Transform result; @@ -44465,7 +46750,7 @@ int _wrap_FixedJoint_setIndex(int resc, mxArray *resv[], int argc, mxArray *argv SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setIndex" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); } arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FixedJoint_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -44844,6 +47129,212 @@ int _wrap_FixedJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArray * } +int _wrap_FixedJoint_getJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointDynamicsType result; + + if (!SWIG_check_num_args("FixedJoint_getJointDynamicsType",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getJointDynamicsType" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + result = (iDynTree::JointDynamicsType)((iDynTree::FixedJoint const *)arg1)->getJointDynamicsType(); + _out = SWIG_From_int(static_cast< int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_setJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + iDynTree::JointDynamicsType arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("FixedJoint_setJointDynamicsType",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setJointDynamicsType" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_setJointDynamicsType" "', argument " "2"" of type '" "iDynTree::JointDynamicsType""'"); + } + arg2 = static_cast< iDynTree::JointDynamicsType >(val2); + result = (bool)(arg1)->setJointDynamicsType(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("FixedJoint_getDamping",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getDamping" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_getDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::FixedJoint const *)arg1)->getDamping(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_getStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("FixedJoint_getStaticFriction",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_getStaticFriction" "', argument " "1"" of type '" "iDynTree::FixedJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_getStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::FixedJoint const *)arg1)->getStaticFriction(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_setDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("FixedJoint_setDamping",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setDamping" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_setDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "FixedJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FixedJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setDamping(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FixedJoint_setStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FixedJoint *arg1 = (iDynTree::FixedJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("FixedJoint_setStaticFriction",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FixedJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FixedJoint_setStaticFriction" "', argument " "1"" of type '" "iDynTree::FixedJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::FixedJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "FixedJoint_setStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "FixedJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FixedJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setStaticFriction(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_delete_MovableJointImpl1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::MovableJointImpl< 1,1 > *arg1 = (iDynTree::MovableJointImpl< 1,1 > *) 0 ; void *argp1 = 0 ; @@ -44936,7 +47427,7 @@ int _wrap_MovableJointImpl1_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl1_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 1,1 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 1,1 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl1_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -45179,7 +47670,7 @@ int _wrap_MovableJointImpl2_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl2_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 2,2 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 2,2 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl2_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -45422,7 +47913,7 @@ int _wrap_MovableJointImpl3_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl3_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 3,3 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 3,3 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl3_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -45665,7 +48156,7 @@ int _wrap_MovableJointImpl4_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl4_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 4,4 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 4,4 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl4_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -45908,7 +48399,7 @@ int _wrap_MovableJointImpl5_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl5_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 5,5 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 5,5 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl5_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -46151,7 +48642,7 @@ int _wrap_MovableJointImpl6_setIndex(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MovableJointImpl6_setIndex" "', argument " "1"" of type '" "iDynTree::MovableJointImpl< 6,6 > *""'"); } arg1 = reinterpret_cast< iDynTree::MovableJointImpl< 6,6 > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__ptrdiff_t, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_ptrdiff_t, 0 ); if (!SWIG_IsOK(res2)) { SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MovableJointImpl6_setIndex" "', argument " "2"" of type '" "iDynTree::JointIndex &""'"); } @@ -48033,6 +50524,212 @@ int _wrap_RevoluteJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArra } +int _wrap_RevoluteJoint_getJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointDynamicsType result; + + if (!SWIG_check_num_args("RevoluteJoint_getJointDynamicsType",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_getJointDynamicsType" "', argument " "1"" of type '" "iDynTree::RevoluteJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + result = (iDynTree::JointDynamicsType)((iDynTree::RevoluteJoint const *)arg1)->getJointDynamicsType(); + _out = SWIG_From_int(static_cast< int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RevoluteJoint_setJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + iDynTree::JointDynamicsType arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("RevoluteJoint_setJointDynamicsType",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_setJointDynamicsType" "', argument " "1"" of type '" "iDynTree::RevoluteJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RevoluteJoint_setJointDynamicsType" "', argument " "2"" of type '" "iDynTree::JointDynamicsType""'"); + } + arg2 = static_cast< iDynTree::JointDynamicsType >(val2); + result = (bool)(arg1)->setJointDynamicsType(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RevoluteJoint_getDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("RevoluteJoint_getDamping",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_getDamping" "', argument " "1"" of type '" "iDynTree::RevoluteJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RevoluteJoint_getDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::RevoluteJoint const *)arg1)->getDamping(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RevoluteJoint_getStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("RevoluteJoint_getStaticFriction",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_getStaticFriction" "', argument " "1"" of type '" "iDynTree::RevoluteJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RevoluteJoint_getStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::RevoluteJoint const *)arg1)->getStaticFriction(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RevoluteJoint_setDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("RevoluteJoint_setDamping",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_setDamping" "', argument " "1"" of type '" "iDynTree::RevoluteJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RevoluteJoint_setDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "RevoluteJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RevoluteJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setDamping(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_RevoluteJoint_setStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::RevoluteJoint *arg1 = (iDynTree::RevoluteJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("RevoluteJoint_setStaticFriction",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__RevoluteJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RevoluteJoint_setStaticFriction" "', argument " "1"" of type '" "iDynTree::RevoluteJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::RevoluteJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "RevoluteJoint_setStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "RevoluteJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RevoluteJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setStaticFriction(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_new_PrismaticJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; iDynTree::PrismaticJoint *result = 0 ; @@ -49711,6 +52408,212 @@ int _wrap_PrismaticJoint_setPosLimits(int resc, mxArray *resv[], int argc, mxArr } +int _wrap_PrismaticJoint_getJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointDynamicsType result; + + if (!SWIG_check_num_args("PrismaticJoint_getJointDynamicsType",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_getJointDynamicsType" "', argument " "1"" of type '" "iDynTree::PrismaticJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + result = (iDynTree::JointDynamicsType)((iDynTree::PrismaticJoint const *)arg1)->getJointDynamicsType(); + _out = SWIG_From_int(static_cast< int >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_PrismaticJoint_setJointDynamicsType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + iDynTree::JointDynamicsType arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("PrismaticJoint_setJointDynamicsType",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_setJointDynamicsType" "', argument " "1"" of type '" "iDynTree::PrismaticJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "PrismaticJoint_setJointDynamicsType" "', argument " "2"" of type '" "iDynTree::JointDynamicsType""'"); + } + arg2 = static_cast< iDynTree::JointDynamicsType >(val2); + result = (bool)(arg1)->setJointDynamicsType(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_PrismaticJoint_getDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("PrismaticJoint_getDamping",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_getDamping" "', argument " "1"" of type '" "iDynTree::PrismaticJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "PrismaticJoint_getDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::PrismaticJoint const *)arg1)->getDamping(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_PrismaticJoint_getStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("PrismaticJoint_getStaticFriction",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_getStaticFriction" "', argument " "1"" of type '" "iDynTree::PrismaticJoint const *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "PrismaticJoint_getStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (double)((iDynTree::PrismaticJoint const *)arg1)->getStaticFriction(arg2); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_PrismaticJoint_setDamping(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("PrismaticJoint_setDamping",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_setDamping" "', argument " "1"" of type '" "iDynTree::PrismaticJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "PrismaticJoint_setDamping" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "PrismaticJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PrismaticJoint_setDamping" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setDamping(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_PrismaticJoint_setStaticFriction(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::PrismaticJoint *arg1 = (iDynTree::PrismaticJoint *) 0 ; + size_t arg2 ; + double *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("PrismaticJoint_setStaticFriction",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__PrismaticJoint, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "PrismaticJoint_setStaticFriction" "', argument " "1"" of type '" "iDynTree::PrismaticJoint *""'"); + } + arg1 = reinterpret_cast< iDynTree::PrismaticJoint * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "PrismaticJoint_setStaticFriction" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_double, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "PrismaticJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "PrismaticJoint_setStaticFriction" "', argument " "3"" of type '" "double &""'"); + } + arg3 = reinterpret_cast< double * >(argp3); + result = (bool)(arg1)->setStaticFriction(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_new_Traversal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; iDynTree::Traversal *result = 0 ; @@ -51916,6 +54819,30 @@ int _wrap_ExternalMesh_getFilename(int resc, mxArray *resv[], int argc, mxArray } +int _wrap_ExternalMesh_getPackageDirs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ExternalMesh *arg1 = (iDynTree::ExternalMesh *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::vector< std::string,std::allocator< std::string > > *result = 0 ; + + if (!SWIG_check_num_args("ExternalMesh_getPackageDirs",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ExternalMesh, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExternalMesh_getPackageDirs" "', argument " "1"" of type '" "iDynTree::ExternalMesh const *""'"); + } + arg1 = reinterpret_cast< iDynTree::ExternalMesh * >(argp1); + result = (std::vector< std::string,std::allocator< std::string > > *) &((iDynTree::ExternalMesh const *)arg1)->getPackageDirs(); + _out = swig::from(static_cast< std::vector< std::string,std::allocator< std::string > > >(*result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_ExternalMesh_getFileLocationOnLocalFileSystem(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExternalMesh *arg1 = (iDynTree::ExternalMesh *) 0 ; void *argp1 = 0 ; @@ -51978,6 +54905,44 @@ int _wrap_ExternalMesh_setFilename(int resc, mxArray *resv[], int argc, mxArray } +int _wrap_ExternalMesh_setPackageDirs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ExternalMesh *arg1 = (iDynTree::ExternalMesh *) 0 ; + std::vector< std::string,std::allocator< std::string > > *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + mxArray * _out; + + if (!SWIG_check_num_args("ExternalMesh_setPackageDirs",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ExternalMesh, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExternalMesh_setPackageDirs" "', argument " "1"" of type '" "iDynTree::ExternalMesh *""'"); + } + arg1 = reinterpret_cast< iDynTree::ExternalMesh * >(argp1); + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res2 = swig::asptr(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExternalMesh_setPackageDirs" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExternalMesh_setPackageDirs" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg2 = ptr; + } + (arg1)->setPackageDirs((std::vector< std::string,std::allocator< std::string > > const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + return 1; +} + + int _wrap_ExternalMesh_getScale(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExternalMesh *arg1 = (iDynTree::ExternalMesh *) 0 ; void *argp1 = 0 ; @@ -52384,30 +55349,29 @@ int _wrap_ModelSolidShapes_getLinkSolidShapes(int resc, mxArray *resv[], int arg } -int _wrap_Neighbor_neighborLink_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; +SWIGINTERN int _wrap_NR_OF_SENSOR_TYPES_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + resv[0] = SWIG_From_int(static_cast< int >(iDynTree::NR_OF_SENSOR_TYPES)); + return 0; +} + + +int _wrap_isLinkSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorType arg1 ; + int val1 ; + int ecode1 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("Neighbor_neighborLink_set",argc,2,2,0)) { + if (!SWIG_check_num_args("isLinkSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborLink_set" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); - } - arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Neighbor_neighborLink_set" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + ecode1 = SWIG_AsVal_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "isLinkSensor" "', argument " "1"" of type '" "iDynTree::SensorType""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - if (arg1) (arg1)->neighborLink = arg2; - _out = (mxArray*)0; + arg1 = static_cast< iDynTree::SensorType >(val1); + result = (bool)iDynTree::isLinkSensor(arg1); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52415,23 +55379,47 @@ int _wrap_Neighbor_neighborLink_set(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Neighbor_neighborLink_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_isJointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorType arg1 ; + int val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + bool result; - if (!SWIG_check_num_args("Neighbor_neighborLink_get",argc,1,1,0)) { + if (!SWIG_check_num_args("isJointSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborLink_get" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + ecode1 = SWIG_AsVal_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "isJointSensor" "', argument " "1"" of type '" "iDynTree::SensorType""'"); + } + arg1 = static_cast< iDynTree::SensorType >(val1); + result = (bool)iDynTree::isJointSensor(arg1); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_getSensorTypeSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorType arg1 ; + int val1 ; + int ecode1 = 0 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("getSensorTypeSize",argc,1,1,0)) { + SWIG_fail; } - arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); - result = ((arg1)->neighborLink); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + ecode1 = SWIG_AsVal_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getSensorTypeSize" "', argument " "1"" of type '" "iDynTree::SensorType""'"); + } + arg1 = static_cast< iDynTree::SensorType >(val1); + result = iDynTree::getSensorTypeSize(arg1); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52439,29 +55427,25 @@ int _wrap_Neighbor_neighborLink_get(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Neighbor_neighborJoint_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; - iDynTree::JointIndex arg2 ; +int _wrap_delete_Sensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("Neighbor_neighborJoint_set",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Sensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborJoint_set" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Sensor" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Neighbor_neighborJoint_set" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); - } - arg2 = static_cast< iDynTree::JointIndex >(val2); - if (arg1) (arg1)->neighborJoint = arg2; _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -52470,23 +55454,23 @@ int _wrap_Neighbor_neighborJoint_set(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_Neighbor_neighborJoint_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; +int _wrap_Sensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointIndex result; + std::string result; - if (!SWIG_check_num_args("Neighbor_neighborJoint_get",argc,1,1,0)) { + if (!SWIG_check_num_args("Sensor_getName",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborJoint_get" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_getName" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); - result = ((arg1)->neighborJoint); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + result = ((iDynTree::Sensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52494,16 +55478,23 @@ int _wrap_Neighbor_neighborJoint_get(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Sensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Neighbor *result = 0 ; + iDynTree::SensorType result; - if (!SWIG_check_num_args("new_Neighbor",argc,0,0,0)) { + if (!SWIG_check_num_args("Sensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Neighbor *)new iDynTree::Neighbor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Neighbor, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_getSensorType" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::Sensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52511,26 +55502,23 @@ int _wrap_new_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; +int _wrap_Sensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_Neighbor",argc,1,1,0)) { + if (!SWIG_check_num_args("Sensor_isValid",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Neighbor" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); - } - arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_isValid" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + result = (bool)((iDynTree::Sensor const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52538,43 +55526,62 @@ int _wrap_delete_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_Model__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Sensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::Model *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_Model",argc,0,0,0)) { + if (!SWIG_check_num_args("Sensor_setName",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::Model *)new iDynTree::Model(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Model, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_setName" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setName((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_new_Model__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Sensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Model *result = 0 ; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("new_Model",argc,1,1,0)) { + if (!SWIG_check_num_args("Sensor_clone",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Model" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Model" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_clone" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::Model *)new iDynTree::Model((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Model, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::Sensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52582,45 +55589,69 @@ int _wrap_new_Model__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_Model(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_Model__SWIG_0(resc,resv,argc,argv); +int _wrap_Sensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("Sensor_isConsistent",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_Model__SWIG_1(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_isConsistent" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Model'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Model::Model()\n" - " iDynTree::Model::Model(iDynTree::Model const &)\n"); + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::Sensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_Model_copy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_Sensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Model result; + bool result; - if (!SWIG_check_num_args("Model_copy",argc,1,1,0)) { + if (!SWIG_check_num_args("Sensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_copy" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_updateIndices" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->copy(); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52628,22 +55659,22 @@ int _wrap_Model_copy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_Model(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_delete_JointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_Model",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_JointSensor",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Model" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointSensor" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); if (is_owned) { delete arg1; } @@ -52655,23 +55686,23 @@ int _wrap_delete_Model(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Model_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_JointSensor_getParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + std::string result; - if (!SWIG_check_num_args("Model_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("JointSensor_getParentJoint",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_getParentJoint" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); + result = ((iDynTree::JointSensor const *)arg1)->getParentJoint(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52679,31 +55710,23 @@ int _wrap_Model_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Model_getLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_JointSensor_getParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - std::string result; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("Model_getLinkName",argc,2,2,0)) { + if (!SWIG_check_num_args("JointSensor_getParentJointIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_getParentJointIndex" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLinkName" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = ((iDynTree::Model const *)arg1)->getLinkName(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); + result = ((iDynTree::JointSensor const *)arg1)->getParentJointIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52711,36 +55734,36 @@ int _wrap_Model_getLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Model_getLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_JointSensor_setParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::LinkIndex result; + bool result; - if (!SWIG_check_num_args("Model_getLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("JointSensor_setParentJoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_setParentJoint" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); { std::string *ptr = (std::string *)0; res2 = SWIG_AsPtr_std_string(argv[1], &ptr); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getLinkIndex" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getLinkIndex" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); } arg2 = ptr; } - result = ((iDynTree::Model const *)arg1)->getLinkIndex((std::string const &)*arg2); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + result = (bool)(arg1)->setParentJoint((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; if (SWIG_IsNewObj(res2)) delete arg2; return 0; @@ -52750,30 +55773,32 @@ int _wrap_Model_getLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Model_isValidLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_JointSensor_setParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; + iDynTree::JointIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + iDynTree::JointIndex temp2 ; ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_isValidLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("JointSensor_setParentJointIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidLinkIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_setParentJointIndex" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointSensor_setParentJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (bool)((iDynTree::Model const *)arg1)->isValidLinkIndex(arg2); + temp2 = static_cast< iDynTree::JointIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentJointIndex((iDynTree::JointIndex const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -52782,63 +55807,34 @@ int _wrap_Model_isValidLinkIndex(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Model_getLink__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_JointSensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkPtr result; + bool result; - if (!SWIG_check_num_args("Model_getLink",argc,2,2,0)) { + if (!SWIG_check_num_args("JointSensor_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_isConsistent" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::LinkPtr)(arg1)->getLink(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Model_getLink__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - iDynTree::LinkConstPtr result; - - if (!SWIG_check_num_args("Model_getLink",argc,2,2,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (iDynTree::LinkConstPtr)((iDynTree::Model const *)arg1)->getLink(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::JointSensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52846,113 +55842,50 @@ int _wrap_Model_getLink__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Model_getLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Model_getLink__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Model_getLink__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_getLink'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Model::getLink(iDynTree::LinkIndex const)\n" - " iDynTree::Model::getLink(iDynTree::LinkIndex const) const\n"); - return 1; -} - - -int _wrap_Model_addLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - iDynTree::Link *arg3 = 0 ; +int _wrap_delete_LinkSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; - if (!SWIG_check_num_args("Model_addLink",argc,3,3,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_LinkSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Link, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addLink" "', argument " "3"" of type '" "iDynTree::Link const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkSensor" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addLink" "', argument " "3"" of type '" "iDynTree::Link const &""'"); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + if (is_owned) { + delete arg1; } - arg3 = reinterpret_cast< iDynTree::Link * >(argp3); - result = (arg1)->addLink((std::string const &)*arg2,(iDynTree::Link const &)*arg3); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_Model_getNrOfJoints(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_LinkSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + std::string result; - if (!SWIG_check_num_args("Model_getNrOfJoints",argc,1,1,0)) { + if (!SWIG_check_num_args("LinkSensor_getParentLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfJoints" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getNrOfJoints(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + result = ((iDynTree::LinkSensor const *)arg1)->getParentLink(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52960,31 +55893,23 @@ int _wrap_Model_getNrOfJoints(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Model_getJointName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::JointIndex arg2 ; +int _wrap_LinkSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - std::string result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("Model_getJointName",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkSensor_getParentLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJointName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJointName" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); - } - arg2 = static_cast< iDynTree::JointIndex >(val2); - result = ((iDynTree::Model const *)arg1)->getJointName(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + result = ((iDynTree::LinkSensor const *)arg1)->getParentLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -52992,23 +55917,23 @@ int _wrap_Model_getJointName(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Model_getTotalMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_LinkSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double result; + iDynTree::Transform result; - if (!SWIG_check_num_args("Model_getTotalMass",argc,1,1,0)) { + if (!SWIG_check_num_args("LinkSensor_getLinkSensorTransform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getTotalMass" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (double)((iDynTree::Model const *)arg1)->getTotalMass(); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + result = ((iDynTree::LinkSensor const *)arg1)->getLinkSensorTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -53016,36 +55941,36 @@ int _wrap_Model_getTotalMass(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Model_getJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_LinkSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::JointIndex result; + bool result; - if (!SWIG_check_num_args("Model_getJointIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkSensor_setParentLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJointIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); { std::string *ptr = (std::string *)0; res2 = SWIG_AsPtr_std_string(argv[1], &ptr); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getJointIndex" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getJointIndex" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); } arg2 = ptr; } - result = ((iDynTree::Model const *)arg1)->getJointIndex((std::string const &)*arg2); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + result = (bool)(arg1)->setParentLink((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; if (SWIG_IsNewObj(res2)) delete arg2; return 0; @@ -53055,168 +55980,32 @@ int _wrap_Model_getJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Model_getJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::JointIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - iDynTree::IJointPtr result; - - if (!SWIG_check_num_args("Model_getJoint",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJoint" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); - } - arg2 = static_cast< iDynTree::JointIndex >(val2); - result = (iDynTree::IJointPtr)(arg1)->getJoint(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Model_getJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::JointIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - iDynTree::IJointConstPtr result; - - if (!SWIG_check_num_args("Model_getJoint",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJoint" "', argument " "1"" of type '" "iDynTree::Model const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJoint" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); - } - arg2 = static_cast< iDynTree::JointIndex >(val2); - result = (iDynTree::IJointConstPtr)((iDynTree::Model const *)arg1)->getJoint(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Model_getJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Model_getJoint__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Model_getJoint__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_getJoint'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Model::getJoint(iDynTree::JointIndex const)\n" - " iDynTree::Model::getJoint(iDynTree::JointIndex const) const\n"); - return 1; -} - - -int _wrap_Model_isValidJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::JointIndex arg2 ; +int _wrap_LinkSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + iDynTree::LinkIndex temp2 ; ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_isValidJointIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkSensor_setParentLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidJointIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg2 = static_cast< iDynTree::JointIndex >(val2); - result = (bool)((iDynTree::Model const *)arg1)->isValidJointIndex(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Model_isLinkNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("Model_isLinkNameUsed",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isLinkNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isLinkNameUsed" "', argument " "2"" of type '" "std::string const""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - result = (bool)((iDynTree::Model const *)arg1)->isLinkNameUsed(arg2); + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -53225,32 +56014,33 @@ int _wrap_Model_isLinkNameUsed(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Model_isJointNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string arg2 ; +int _wrap_LinkSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_isJointNameUsed",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkSensor_setLinkSensorTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isJointNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isJointNameUsed" "', argument " "2"" of type '" "std::string const""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - result = (bool)((iDynTree::Model const *)arg1)->isJointNameUsed(arg2); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -53259,32 +56049,33 @@ int _wrap_Model_isJointNameUsed(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Model_isFrameNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string arg2 ; +int _wrap_LinkSensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_isFrameNameUsed",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkSensor_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isFrameNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isFrameNameUsed" "', argument " "2"" of type '" "std::string const""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - result = (bool)((iDynTree::Model const *)arg1)->isFrameNameUsed(arg2); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::LinkSensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -53293,427 +56084,223 @@ int _wrap_Model_isFrameNameUsed(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_Model_addJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - iDynTree::IJointConstPtr arg3 = (iDynTree::IJointConstPtr) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - void *argp3 = 0 ; - int res3 = 0 ; +int _wrap_new_SensorsList__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::JointIndex result; + iDynTree::SensorsList *result = 0 ; - if (!SWIG_check_num_args("Model_addJoint",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SensorsList",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJoint" "', argument " "3"" of type '" "iDynTree::IJointConstPtr""'"); - } - arg3 = reinterpret_cast< iDynTree::IJointConstPtr >(argp3); - result = (arg1)->addJoint((std::string const &)*arg2,arg3); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + (void)argv; + result = (iDynTree::SensorsList *)new iDynTree::SensorsList(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 1 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_Model_addJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - std::string *arg3 = 0 ; - std::string *arg4 = 0 ; - iDynTree::IJointConstPtr arg5 = (iDynTree::IJointConstPtr) 0 ; - void *argp1 = 0 ; +int _wrap_new_SensorsList__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - int res3 = SWIG_OLDOBJ ; - int res4 = SWIG_OLDOBJ ; - void *argp5 = 0 ; - int res5 = 0 ; mxArray * _out; - iDynTree::JointIndex result; + iDynTree::SensorsList *result = 0 ; - if (!SWIG_check_num_args("Model_addJoint",argc,5,5,0)) { + if (!SWIG_check_num_args("new_SensorsList",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsList, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJoint" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; - } - { - std::string *ptr = (std::string *)0; - res4 = SWIG_AsPtr_std_string(argv[3], &ptr); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addJoint" "', argument " "4"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "4"" of type '" "std::string const &""'"); - } - arg4 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); } - res5 = SWIG_ConvertPtr(argv[4], &argp5,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_addJoint" "', argument " "5"" of type '" "iDynTree::IJointConstPtr""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); } - arg5 = reinterpret_cast< iDynTree::IJointConstPtr >(argp5); - result = (arg1)->addJoint((std::string const &)*arg2,(std::string const &)*arg3,(std::string const &)*arg4,arg5); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + result = (iDynTree::SensorsList *)new iDynTree::SensorsList((iDynTree::SensorsList const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 1 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_Model_addJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__IJoint, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Model_addJoint__SWIG_0(resc,resv,argc,argv); - } - } - } +int _wrap_new_SensorsList(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SensorsList__SWIG_0(resc,resv,argc,argv); } - if (argc == 5) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); _v = SWIG_CheckState(res); if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__IJoint, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Model_addJoint__SWIG_1(resc,resv,argc,argv); - } - } - } - } + return _wrap_new_SensorsList__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_addJoint'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SensorsList'." " Possible C/C++ prototypes are:\n" - " iDynTree::Model::addJoint(std::string const &,iDynTree::IJointConstPtr)\n" - " iDynTree::Model::addJoint(std::string const &,std::string const &,std::string const &,iDynTree::IJointConstPtr)\n"); + " iDynTree::SensorsList::SensorsList()\n" + " iDynTree::SensorsList::SensorsList(iDynTree::SensorsList const &)\n"); return 1; } -int _wrap_Model_addJointAndLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - std::string *arg3 = 0 ; - iDynTree::IJointConstPtr arg4 = (iDynTree::IJointConstPtr) 0 ; - std::string *arg5 = 0 ; - iDynTree::Link *arg6 = 0 ; +int _wrap_delete_SensorsList(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - int res3 = SWIG_OLDOBJ ; - void *argp4 = 0 ; - int res4 = 0 ; - int res5 = SWIG_OLDOBJ ; - void *argp6 = 0 ; - int res6 = 0 ; mxArray * _out; - iDynTree::JointIndex result; - if (!SWIG_check_num_args("Model_addJointAndLink",argc,6,6,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SensorsList",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJointAndLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJointAndLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJointAndLink" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; - } - res4 = SWIG_ConvertPtr(argv[3], &argp4,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addJointAndLink" "', argument " "4"" of type '" "iDynTree::IJointConstPtr""'"); - } - arg4 = reinterpret_cast< iDynTree::IJointConstPtr >(argp4); - { - std::string *ptr = (std::string *)0; - res5 = SWIG_AsPtr_std_string(argv[4], &ptr); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_addJointAndLink" "', argument " "5"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "5"" of type '" "std::string const &""'"); - } - arg5 = ptr; - } - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__Link, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "Model_addJointAndLink" "', argument " "6"" of type '" "iDynTree::Link &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "6"" of type '" "iDynTree::Link &""'"); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + if (is_owned) { + delete arg1; } - arg6 = reinterpret_cast< iDynTree::Link * >(argp6); - result = (arg1)->addJointAndLink((std::string const &)*arg2,(std::string const &)*arg3,arg4,(std::string const &)*arg5,*arg6); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res5)) delete arg5; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res5)) delete arg5; return 1; } -int _wrap_Model_insertLinkToExistingJointAndAddJointForDisplacedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - std::string *arg3 = 0 ; - iDynTree::Transform *arg4 = 0 ; - std::string *arg5 = 0 ; - iDynTree::IJointConstPtr arg6 = (iDynTree::IJointConstPtr) 0 ; - std::string *arg7 = 0 ; - iDynTree::Link *arg8 = 0 ; +int _wrap_SensorsList_addSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::Sensor *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - int res3 = SWIG_OLDOBJ ; - void *argp4 ; - int res4 = 0 ; - int res5 = SWIG_OLDOBJ ; - void *argp6 = 0 ; - int res6 = 0 ; - int res7 = SWIG_OLDOBJ ; - void *argp8 = 0 ; - int res8 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::JointIndex result; + std::ptrdiff_t result; - if (!SWIG_check_num_args("Model_insertLinkToExistingJointAndAddJointForDisplacedLink",argc,8,8,0)) { + if (!SWIG_check_num_args("SensorsList_addSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; - } - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "4"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "4"" of type '" "iDynTree::Transform const &""'"); - } - arg4 = reinterpret_cast< iDynTree::Transform * >(argp4); - { - std::string *ptr = (std::string *)0; - res5 = SWIG_AsPtr_std_string(argv[4], &ptr); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "5"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "5"" of type '" "std::string const &""'"); - } - arg5 = ptr; - } - res6 = SWIG_ConvertPtr(argv[5], &argp6,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "6"" of type '" "iDynTree::IJointConstPtr""'"); - } - arg6 = reinterpret_cast< iDynTree::IJointConstPtr >(argp6); - { - std::string *ptr = (std::string *)0; - res7 = SWIG_AsPtr_std_string(argv[6], &ptr); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "7"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "7"" of type '" "std::string const &""'"); - } - arg7 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_addSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__Link, 0 ); - if (!SWIG_IsOK(res8)) { - SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "8"" of type '" "iDynTree::Link &""'"); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Sensor, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsList_addSensor" "', argument " "2"" of type '" "iDynTree::Sensor const &""'"); } - if (!argp8) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "8"" of type '" "iDynTree::Link &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_addSensor" "', argument " "2"" of type '" "iDynTree::Sensor const &""'"); } - arg8 = reinterpret_cast< iDynTree::Link * >(argp8); - result = (arg1)->insertLinkToExistingJointAndAddJointForDisplacedLink((std::string const &)*arg2,(std::string const &)*arg3,(iDynTree::Transform const &)*arg4,(std::string const &)*arg5,arg6,(std::string const &)*arg7,*arg8); + arg2 = reinterpret_cast< iDynTree::Sensor * >(argp2); + result = (arg1)->addSensor((iDynTree::Sensor const &)*arg2); _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res5)) delete arg5; - if (SWIG_IsNewObj(res7)) delete arg7; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; - if (SWIG_IsNewObj(res3)) delete arg3; - if (SWIG_IsNewObj(res5)) delete arg5; - if (SWIG_IsNewObj(res7)) delete arg7; return 1; } -int _wrap_Model_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsList_setSerialization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - size_t result; + bool result; - if (!SWIG_check_num_args("Model_getNrOfPosCoords",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsList_setSerialization",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_setSerialization" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getNrOfPosCoords(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_setSerialization" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_setSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_setSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg3 = ptr; + } + result = (bool)(arg1)->setSerialization((iDynTree::SensorType const &)*arg2,(std::vector< std::string,std::allocator< std::string > > const &)*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_Model_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsList_getSerialization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - size_t result; + bool result; - if (!SWIG_check_num_args("Model_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsList_getSerialization",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSerialization" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSerialization" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_std__vectorT_std__string_std__allocatorT_std__string_t_t, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > &""'"); + } + arg3 = reinterpret_cast< std::vector< std::string,std::allocator< std::string > > * >(argp3); + result = (bool)(arg1)->getSerialization((iDynTree::SensorType const &)*arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -53721,22 +56308,33 @@ int _wrap_Model_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Model_getNrOfFrames(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsList_getNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; mxArray * _out; - size_t result; + std::size_t result; - if (!SWIG_check_num_args("Model_getNrOfFrames",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsList_getNrOfSensors",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfFrames" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getNrOfFrames(); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + result = ((iDynTree::SensorsList const *)arg1)->getNrOfSensors((iDynTree::SensorType const &)*arg2); _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -53745,170 +56343,187 @@ int _wrap_Model_getNrOfFrames(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Model_addAdditionalFrameToLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; +int _wrap_SensorsList_getSensorIndex__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; std::string *arg3 = 0 ; - iDynTree::Transform arg4 ; + std::ptrdiff_t *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; int res3 = SWIG_OLDOBJ ; - void *argp4 ; + void *argp4 = 0 ; int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_addAdditionalFrameToLink",argc,4,4,0)) { + if (!SWIG_check_num_args("SensorsList_getSensorIndex",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addAdditionalFrameToLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensorIndex" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addAdditionalFrameToLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensorIndex" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; } { std::string *ptr = (std::string *)0; res3 = SWIG_AsPtr_std_string(argv[2], &ptr); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addAdditionalFrameToLink" "', argument " "3"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "3"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); } arg3 = ptr; } - { - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addAdditionalFrameToLink" "', argument " "4"" of type '" "iDynTree::Transform""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "4"" of type '" "iDynTree::Transform""'"); - } else { - arg4 = *(reinterpret_cast< iDynTree::Transform * >(argp4)); - } + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_ptrdiff_t, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsList_getSensorIndex" "', argument " "4"" of type '" "std::ptrdiff_t &""'"); } - result = (bool)(arg1)->addAdditionalFrameToLink((std::string const &)*arg2,(std::string const &)*arg3,arg4); + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "4"" of type '" "std::ptrdiff_t &""'"); + } + arg4 = reinterpret_cast< std::ptrdiff_t * >(argp4); + result = (bool)((iDynTree::SensorsList const *)arg1)->getSensorIndex((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3,*arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_Model_getFrameName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::FrameIndex arg2 ; +int _wrap_SensorsList_getSensorIndex__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::string *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - std::string result; + std::ptrdiff_t result; - if (!SWIG_check_num_args("Model_getFrameName",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getSensorIndex",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensorIndex" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameName" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); - } - arg2 = static_cast< iDynTree::FrameIndex >(val2); - result = ((iDynTree::Model const *)arg1)->getFrameName(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_Model_getFrameIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - mxArray * _out; - iDynTree::FrameIndex result; - - if (!SWIG_check_num_args("Model_getFrameIndex",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensorIndex" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); { std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getFrameIndex" "', argument " "2"" of type '" "std::string const &""'"); + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getFrameIndex" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); } - arg2 = ptr; + arg3 = ptr; } - result = ((iDynTree::Model const *)arg1)->getFrameIndex((std::string const &)*arg2); + result = ((iDynTree::SensorsList const *)arg1)->getSensorIndex((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3); _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_Model_isValidFrameIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::FrameIndex arg2 ; +int _wrap_SensorsList_getSensorIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsList_getSensorIndex__SWIG_1(resc,resv,argc,argv); + } + } + } + } + if (argc == 4) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_ptrdiff_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsList_getSensorIndex__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsList_getSensorIndex'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SensorsList::getSensorIndex(iDynTree::SensorType const &,std::string const &,std::ptrdiff_t &) const\n" + " iDynTree::SensorsList::getSensorIndex(iDynTree::SensorType const &,std::string const &) const\n"); + return 1; +} + + +int _wrap_SensorsList_getSizeOfAllSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - bool result; + size_t result; - if (!SWIG_check_num_args("Model_isValidFrameIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getSizeOfAllSensorsMeasurements",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidFrameIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSizeOfAllSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidFrameIndex" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); - } - arg2 = static_cast< iDynTree::FrameIndex >(val2); - result = (bool)((iDynTree::Model const *)arg1)->isValidFrameIndex(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + result = ((iDynTree::SensorsList const *)arg1)->getSizeOfAllSensorsMeasurements(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -53916,31 +56531,42 @@ int _wrap_Model_isValidFrameIndex(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Model_getFrameTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::FrameIndex arg2 ; +int _wrap_SensorsList_getSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::Transform result; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("Model_getFrameTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getSensor",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameTransform" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameTransform" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsList_getSensor" "', argument " "3"" of type '" "std::ptrdiff_t""'"); } - arg2 = static_cast< iDynTree::FrameIndex >(val2); - result = ((iDynTree::Model const *)arg1)->getFrameTransform(arg2); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg3 = static_cast< std::ptrdiff_t >(val3); + result = (iDynTree::Sensor *)((iDynTree::SensorsList const *)arg1)->getSensor((iDynTree::SensorType const &)*arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -53948,31 +56574,34 @@ int _wrap_Model_getFrameTransform(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_Model_getFrameLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::FrameIndex arg2 ; +int _wrap_SensorsList_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + bool result; - if (!SWIG_check_num_args("Model_getFrameLink",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_isConsistent" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameLink" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); - } - arg2 = static_cast< iDynTree::FrameIndex >(val2); - result = ((iDynTree::Model const *)arg1)->getFrameLink(arg2); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsList_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::SensorsList const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -53980,74 +56609,92 @@ int _wrap_Model_getFrameLink(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_Model_getLinkAdditionalFrames(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; - std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > *arg3 = 0 ; +int _wrap_SensorsList_removeSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::string *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Model_getLinkAdditionalFrames",argc,3,3,0)) { + if (!SWIG_check_num_args("SensorsList_removeSensor",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkAdditionalFrames" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLinkAdditionalFrames" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_getLinkAdditionalFrames" "', argument " "3"" of type '" "std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > &""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getLinkAdditionalFrames" "', argument " "3"" of type '" "std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > &""'"); + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; } - arg3 = reinterpret_cast< std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > * >(argp3); - result = (bool)((iDynTree::Model const *)arg1)->getLinkAdditionalFrames(arg2,*arg3); + result = (bool)(arg1)->removeSensor((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_Model_getNrOfNeighbors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_SensorsList_removeSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - unsigned int result; + bool result; - if (!SWIG_check_num_args("Model_getNrOfNeighbors",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_removeSensor",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfNeighbors" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getNrOfNeighbors" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::ptrdiff_t""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (unsigned int)((iDynTree::Model const *)arg1)->getNrOfNeighbors(arg2); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg3 = static_cast< std::ptrdiff_t >(val3); + result = (bool)(arg1)->removeSensor((iDynTree::SensorType const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54055,39 +56702,84 @@ int _wrap_Model_getNrOfNeighbors(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_Model_getNeighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; - unsigned int arg3 ; +int _wrap_SensorsList_removeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_SensorsList_removeSensor__SWIG_1(resc,resv,argc,argv); + } + } + } + } + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsList_removeSensor__SWIG_0(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsList_removeSensor'." + " Possible C/C++ prototypes are:\n" + " iDynTree::SensorsList::removeSensor(iDynTree::SensorType const &,std::string const &)\n" + " iDynTree::SensorsList::removeSensor(iDynTree::SensorType const &,std::ptrdiff_t const)\n"); + return 1; +} + + +int _wrap_SensorsList_removeAllSensorsOfType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + iDynTree::SensorType *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - unsigned int val3 ; - int ecode3 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; mxArray * _out; - iDynTree::Neighbor result; + bool result; - if (!SWIG_check_num_args("Model_getNeighbor",argc,3,3,0)) { + if (!SWIG_check_num_args("SensorsList_removeAllSensorsOfType",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNeighbor" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeAllSensorsOfType" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getNeighbor" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Model_getNeighbor" "', argument " "3"" of type '" "unsigned int""'"); - } - arg3 = static_cast< unsigned int >(val3); - result = ((iDynTree::Model const *)arg1)->getNeighbor(arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Neighbor(static_cast< const iDynTree::Neighbor& >(result))), SWIGTYPE_p_iDynTree__Neighbor, SWIG_POINTER_OWN | 0 ); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeAllSensorsOfType" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + result = (bool)(arg1)->removeAllSensorsOfType((iDynTree::SensorType const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54095,31 +56787,31 @@ int _wrap_Model_getNeighbor(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_Model_setDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_SensorsList_getSixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; + int val2 ; int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::SixAxisForceTorqueSensor *result = 0 ; - if (!SWIG_check_num_args("Model_setDefaultBaseLink",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getSixAxisForceTorqueSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_setDefaultBaseLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_setDefaultBaseLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSixAxisForceTorqueSensor" "', argument " "2"" of type '" "int""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (bool)(arg1)->setDefaultBaseLink(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< int >(val2); + result = (iDynTree::SixAxisForceTorqueSensor *)iDynTree_SensorsList_getSixAxisForceTorqueSensor((iDynTree::SensorsList const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54127,23 +56819,31 @@ int _wrap_Model_setDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Model_getDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsList_getAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + int arg2 ; void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::AccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("Model_getDefaultBaseLink",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsList_getAccelerometerSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getDefaultBaseLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->getDefaultBaseLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getAccelerometerSensor" "', argument " "2"" of type '" "int""'"); + } + arg2 = static_cast< int >(val2); + result = (iDynTree::AccelerometerSensor *)iDynTree_SensorsList_getAccelerometerSensor((iDynTree::SensorsList const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54151,34 +56851,31 @@ int _wrap_Model_getDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_Model_computeFullTreeTraversal__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::Traversal *arg2 = 0 ; +int _wrap_SensorsList_getGyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + int val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::GyroscopeSensor *result = 0 ; - if (!SWIG_check_num_args("Model_computeFullTreeTraversal",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getGyroscopeSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_computeFullTreeTraversal" "', argument " "1"" of type '" "iDynTree::Model const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getGyroscopeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - result = (bool)((iDynTree::Model const *)arg1)->computeFullTreeTraversal(*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getGyroscopeSensor" "', argument " "2"" of type '" "int""'"); + } + arg2 = static_cast< int >(val2); + result = (iDynTree::GyroscopeSensor *)iDynTree_SensorsList_getGyroscopeSensor((iDynTree::SensorsList const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54186,42 +56883,31 @@ int _wrap_Model_computeFullTreeTraversal__SWIG_0(int resc, mxArray *resv[], int } -int _wrap_Model_computeFullTreeTraversal__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::LinkIndex arg3 ; +int _wrap_SensorsList_getThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; + int val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("Model_computeFullTreeTraversal",argc,3,3,0)) { + if (!SWIG_check_num_args("SensorsList_getThreeAxisAngularAccelerometerSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_computeFullTreeTraversal" "', argument " "1"" of type '" "iDynTree::Model const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Model_computeFullTreeTraversal" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getThreeAxisAngularAccelerometerSensor" "', argument " "2"" of type '" "int""'"); } - arg3 = static_cast< iDynTree::LinkIndex >(val3); - result = (bool)((iDynTree::Model const *)arg1)->computeFullTreeTraversal(*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< int >(val2); + result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)iDynTree_SensorsList_getThreeAxisAngularAccelerometerSensor((iDynTree::SensorsList const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54229,78 +56915,31 @@ int _wrap_Model_computeFullTreeTraversal__SWIG_1(int resc, mxArray *resv[], int } -int _wrap_Model_computeFullTreeTraversal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Model_computeFullTreeTraversal__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_Model_computeFullTreeTraversal__SWIG_1(resc,resv,argc,argv); - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_computeFullTreeTraversal'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Model::computeFullTreeTraversal(iDynTree::Traversal &) const\n" - " iDynTree::Model::computeFullTreeTraversal(iDynTree::Traversal &,iDynTree::LinkIndex const) const\n"); - return 1; -} - - -int _wrap_Model_getInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; +int _wrap_SensorsList_getThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; + int arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + int val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; - if (!SWIG_check_num_args("Model_getInertialParameters",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsList_getThreeAxisForceTorqueContactSensor",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getInertialParameters" "', argument " "1"" of type '" "iDynTree::Model const *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - result = (bool)((iDynTree::Model const *)arg1)->getInertialParameters(*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + ecode2 = SWIG_AsVal_int(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getThreeAxisForceTorqueContactSensor" "', argument " "2"" of type '" "int""'"); + } + arg2 = static_cast< int >(val2); + result = (iDynTree::ThreeAxisForceTorqueContactSensor *)iDynTree_SensorsList_getThreeAxisForceTorqueContactSensor((iDynTree::SensorsList const *)arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54308,34 +56947,16 @@ int _wrap_Model_getInertialParameters(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_Model_updateInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_SensorsMeasurements__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - bool result; + iDynTree::SensorsMeasurements *result = 0 ; - if (!SWIG_check_num_args("Model_updateInertialParameters",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SensorsMeasurements",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_updateInertialParameters" "', argument " "1"" of type '" "iDynTree::Model *""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_updateInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_updateInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - result = (bool)(arg1)->updateInertialParameters((iDynTree::VectorDynSize const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + (void)argv; + result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54343,23 +56964,26 @@ int _wrap_Model_updateInertialParameters(int resc, mxArray *resv[], int argc, mx } -int _wrap_Model_visualSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - void *argp1 = 0 ; +int _wrap_new_SensorsMeasurements__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsList *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::ModelSolidShapes *result = 0 ; + iDynTree::SensorsMeasurements *result = 0 ; - if (!SWIG_check_num_args("Model_visualSolidShapes",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SensorsMeasurements",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsList, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_visualSolidShapes" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::ModelSolidShapes *) &(arg1)->visualSolidShapes(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); + result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements((iDynTree::SensorsList const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54367,23 +56991,26 @@ int _wrap_Model_visualSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_Model_visualSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; - void *argp1 = 0 ; +int _wrap_new_SensorsMeasurements__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::ModelSolidShapes *result = 0 ; + iDynTree::SensorsMeasurements *result = 0 ; - if (!SWIG_check_num_args("Model_visualSolidShapes",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SensorsMeasurements",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_visualSolidShapes" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::ModelSolidShapes *) &((iDynTree::Model const *)arg1)->visualSolidShapes(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const &""'"); + } + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements((iDynTree::SensorsMeasurements const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54391,51 +57018,58 @@ int _wrap_Model_visualSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_Model_visualSolidShapes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SensorsMeasurements__SWIG_0(resc,resv,argc,argv); + } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_Model_visualSolidShapes__SWIG_0(resc,resv,argc,argv); + return _wrap_new_SensorsMeasurements__SWIG_1(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_Model_visualSolidShapes__SWIG_1(resc,resv,argc,argv); + return _wrap_new_SensorsMeasurements__SWIG_2(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_visualSolidShapes'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SensorsMeasurements'." " Possible C/C++ prototypes are:\n" - " iDynTree::Model::visualSolidShapes()\n" - " iDynTree::Model::visualSolidShapes() const\n"); + " iDynTree::SensorsMeasurements::SensorsMeasurements()\n" + " iDynTree::SensorsMeasurements::SensorsMeasurements(iDynTree::SensorsList const &)\n" + " iDynTree::SensorsMeasurements::SensorsMeasurements(iDynTree::SensorsMeasurements const &)\n"); return 1; } -int _wrap_Model_collisionSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_delete_SensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::ModelSolidShapes *result = 0 ; - if (!SWIG_check_num_args("Model_collisionSolidShapes",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SensorsMeasurements",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_collisionSolidShapes" "', argument " "1"" of type '" "iDynTree::Model *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::ModelSolidShapes *) &(arg1)->collisionSolidShapes(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54443,23 +57077,42 @@ int _wrap_Model_collisionSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_Model_collisionSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsMeasurements_setNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::ModelSolidShapes *result = 0 ; + bool result; - if (!SWIG_check_num_args("Model_collisionSolidShapes",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_setNrOfSensors",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_collisionSolidShapes" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::ModelSolidShapes *) &((iDynTree::Model const *)arg1)->collisionSolidShapes(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "3"" of type '" "std::size_t""'"); + } + arg3 = static_cast< std::size_t >(val3); + result = (bool)(arg1)->setNrOfSensors((iDynTree::SensorType const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54467,51 +57120,69 @@ int _wrap_Model_collisionSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_Model_collisionSolidShapes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Model_collisionSolidShapes__SWIG_0(resc,resv,argc,argv); - } +int _wrap_SensorsMeasurements_getNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + mxArray * _out; + std::size_t result; + + if (!SWIG_check_num_args("SensorsMeasurements_getNrOfSensors",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_Model_collisionSolidShapes__SWIG_1(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_collisionSolidShapes'." - " Possible C/C++ prototypes are:\n" - " iDynTree::Model::collisionSolidShapes()\n" - " iDynTree::Model::collisionSolidShapes() const\n"); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + result = ((iDynTree::SensorsMeasurements const *)arg1)->getNrOfSensors((iDynTree::SensorType const &)*arg2); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_Model_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; +int _wrap_SensorsMeasurements_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorsList *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("Model_toString",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_toString" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_resize" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = ((iDynTree::Model const *)arg1)->toString(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsMeasurements_resize" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_resize" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); + result = (bool)(arg1)->resize((iDynTree::SensorsList const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54519,23 +57190,34 @@ int _wrap_Model_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_JointPosDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_SensorsMeasurements_toVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::JointPosDoubleArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_toVector",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_toVector" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsMeasurements_toVector" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_toVector" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->toVector(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54543,16 +57225,55 @@ int _wrap_new_JointPosDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_new_JointPosDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SensorsMeasurements_setMeasurement__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t *arg3 = 0 ; + iDynTree::Wrench *arg4 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + std::ptrdiff_t temp3 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - iDynTree::JointPosDoubleArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,0,0,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_setMeasurement",argc,4,4,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); + } + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); + } + temp3 = static_cast< std::ptrdiff_t >(val3); + arg3 = &temp3; + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench const &""'"); + } + arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); + result = (bool)(arg1)->setMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,(iDynTree::Wrench const &)*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54560,26 +57281,55 @@ int _wrap_new_JointPosDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_JointPosDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_SensorsMeasurements_setMeasurement__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t *arg3 = 0 ; + iDynTree::Vector3 *arg4 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + std::ptrdiff_t temp3 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - iDynTree::JointPosDoubleArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_setMeasurement",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); + } + temp3 = static_cast< std::ptrdiff_t >(val3); + arg3 = &temp3; + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 const &""'"); + } + arg4 = reinterpret_cast< iDynTree::Vector3 * >(argp4); + result = (bool)(arg1)->setMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,(iDynTree::Vector3 const &)*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54587,63 +57337,117 @@ int _wrap_new_JointPosDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, m } -int _wrap_new_JointPosDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_JointPosDoubleArray__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_SensorsMeasurements_setMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 4) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_JointPosDoubleArray__SWIG_2(resc,resv,argc,argv); + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsMeasurements_setMeasurement__SWIG_0(resc,resv,argc,argv); + } + } + } } } - if (argc == 1) { + if (argc == 4) { int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_JointPosDoubleArray__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsMeasurements_setMeasurement__SWIG_1(resc,resv,argc,argv); + } + } + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_JointPosDoubleArray'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsMeasurements_setMeasurement'." " Possible C/C++ prototypes are:\n" - " iDynTree::JointPosDoubleArray::JointPosDoubleArray(std::size_t)\n" - " iDynTree::JointPosDoubleArray::JointPosDoubleArray()\n" - " iDynTree::JointPosDoubleArray::JointPosDoubleArray(iDynTree::Model const &)\n"); + " iDynTree::SensorsMeasurements::setMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Wrench const &)\n" + " iDynTree::SensorsMeasurements::setMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Vector3 const &)\n"); return 1; } -int _wrap_JointPosDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; - std::size_t arg2 ; +int _wrap_SensorsMeasurements_getMeasurement__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t *arg3 = 0 ; + iDynTree::Wrench *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + std::ptrdiff_t temp3 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("JointPosDoubleArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_getMeasurement",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); } - arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; + } + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + temp3 = static_cast< std::ptrdiff_t >(val3); + arg3 = &temp3; + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); + } + arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); + result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->getMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54651,33 +57455,55 @@ int _wrap_JointPosDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_JointPosDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SensorsMeasurements_getMeasurement__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; + iDynTree::SensorType *arg2 = 0 ; + std::ptrdiff_t *arg3 = 0 ; + iDynTree::Vector3 *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + int val2 ; + int ecode2 ; + iDynTree::SensorType temp2 ; + std::ptrdiff_t temp3 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("JointPosDoubleArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_getMeasurement",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); } - arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + ecode2 = SWIG_AsVal_int (argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + } else { + temp2 = static_cast< iDynTree::SensorType >(val2); + arg2 = &temp2; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); + } + temp3 = static_cast< std::ptrdiff_t >(val3); + arg3 = &temp3; + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 &""'"); + } + arg4 = reinterpret_cast< iDynTree::Vector3 * >(argp4); + result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->getMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54685,73 +57511,85 @@ int _wrap_JointPosDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_JointPosDoubleArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_SensorsMeasurements_getMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 4) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_int(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_JointPosDoubleArray_resize__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsMeasurements_getMeasurement__SWIG_0(resc,resv,argc,argv); + } + } } } } - if (argc == 2) { + if (argc == 4) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_int(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_JointPosDoubleArray_resize__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SensorsMeasurements_getMeasurement__SWIG_1(resc,resv,argc,argv); + } + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'JointPosDoubleArray_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsMeasurements_getMeasurement'." " Possible C/C++ prototypes are:\n" - " iDynTree::JointPosDoubleArray::resize(std::size_t)\n" - " iDynTree::JointPosDoubleArray::resize(iDynTree::Model const &)\n"); + " iDynTree::SensorsMeasurements::getMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Wrench &) const\n" + " iDynTree::SensorsMeasurements::getMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Vector3 &) const\n"); return 1; } -int _wrap_JointPosDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SensorsMeasurements_getSizeOfAllSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; + size_t result; - if (!SWIG_check_num_args("JointPosDoubleArray_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("SensorsMeasurements_getSizeOfAllSensorsMeasurements",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_isConsistent" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray const *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointPosDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointPosDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getSizeOfAllSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::JointPosDoubleArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); + result = ((iDynTree::SensorsMeasurements const *)arg1)->getSizeOfAllSensorsMeasurements(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54759,25 +57597,29 @@ int _wrap_JointPosDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, } -int _wrap_delete_JointPosDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; +int _wrap_Neighbor_neighborLink_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_JointPosDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Neighbor_neighborLink_set",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborLink_set" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); } + arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Neighbor_neighborLink_set" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + if (arg1) (arg1)->neighborLink = arg2; _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -54786,23 +57628,23 @@ int _wrap_delete_JointPosDoubleArray(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_new_JointDOFsDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Neighbor_neighborLink_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Neighbor_neighborLink_get",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborLink_get" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); + result = ((arg1)->neighborLink); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54810,16 +57652,30 @@ int _wrap_new_JointDOFsDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_JointDOFsDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Neighbor_neighborJoint_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; + iDynTree::JointIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,0,0,0)) { + if (!SWIG_check_num_args("Neighbor_neighborJoint_set",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborJoint_set" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Neighbor_neighborJoint_set" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + } + arg2 = static_cast< iDynTree::JointIndex >(val2); + if (arg1) (arg1)->neighborJoint = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54827,26 +57683,23 @@ int _wrap_new_JointDOFsDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_JointDOFsDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Neighbor_neighborJoint_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Neighbor_neighborJoint_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Neighbor_neighborJoint_get" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); + result = ((arg1)->neighborJoint); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54854,62 +57707,42 @@ int _wrap_new_JointDOFsDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_new_JointDOFsDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_JointDOFsDoubleArray__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_JointDOFsDoubleArray__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_JointDOFsDoubleArray__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_new_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::Neighbor *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_JointDOFsDoubleArray'." - " Possible C/C++ prototypes are:\n" - " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray(std::size_t)\n" - " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray()\n" - " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray(iDynTree::Model const &)\n"); + if (!SWIG_check_num_args("new_Neighbor",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::Neighbor *)new iDynTree::Neighbor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Neighbor, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_JointDOFsDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; - std::size_t arg2 ; +int _wrap_delete_Neighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Neighbor *arg1 = (iDynTree::Neighbor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("JointDOFsDoubleArray_resize",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_Neighbor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Neighbor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Neighbor" "', argument " "1"" of type '" "iDynTree::Neighbor *""'"); + } + arg1 = reinterpret_cast< iDynTree::Neighbor * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -54918,33 +57751,43 @@ int _wrap_JointDOFsDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_JointDOFsDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; +int _wrap_new_Model__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::Model *result = 0 ; + + if (!SWIG_check_num_args("new_Model",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::Model *)new iDynTree::Model(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Model, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_Model__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; mxArray * _out; + iDynTree::Model *result = 0 ; - if (!SWIG_check_num_args("JointDOFsDoubleArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("new_Model",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_Model" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_Model" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::Model *)new iDynTree::Model((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Model, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -54952,73 +57795,45 @@ int _wrap_JointDOFsDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_JointDOFsDoubleArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_JointDOFsDoubleArray_resize__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_new_Model(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_Model__SWIG_0(resc,resv,argc,argv); } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_JointDOFsDoubleArray_resize__SWIG_0(resc,resv,argc,argv); - } + return _wrap_new_Model__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'JointDOFsDoubleArray_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_Model'." " Possible C/C++ prototypes are:\n" - " iDynTree::JointDOFsDoubleArray::resize(std::size_t)\n" - " iDynTree::JointDOFsDoubleArray::resize(iDynTree::Model const &)\n"); + " iDynTree::Model::Model()\n" + " iDynTree::Model::Model(iDynTree::Model const &)\n"); return 1; } -int _wrap_JointDOFsDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_copy(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Model result; - if (!SWIG_check_num_args("JointDOFsDoubleArray_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_copy",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray const *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_copy" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::JointDOFsDoubleArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->copy(); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55026,22 +57841,22 @@ int _wrap_JointDOFsDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, } -int _wrap_delete_JointDOFsDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; +int _wrap_delete_Model(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_JointDOFsDoubleArray",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_Model",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Model" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); if (is_owned) { delete arg1; } @@ -55053,23 +57868,23 @@ int _wrap_delete_JointDOFsDoubleArray(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_DOFSpatialForceArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Model_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::DOFSpatialForceArray *result = 0 ; + size_t result; - if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getNrOfLinks",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55077,16 +57892,23 @@ int _wrap_new_DOFSpatialForceArray__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialForceArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_getPackageDirs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::DOFSpatialForceArray *result = 0 ; + std::vector< std::string,std::allocator< std::string > > *result = 0 ; - if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,0,0,0)) { + if (!SWIG_check_num_args("Model_getPackageDirs",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getPackageDirs" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (std::vector< std::string,std::allocator< std::string > > *) &((iDynTree::Model const *)arg1)->getPackageDirs(); + _out = swig::from(static_cast< std::vector< std::string,std::allocator< std::string > > >(*result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55094,26 +57916,69 @@ int _wrap_new_DOFSpatialForceArray__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialForceArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_setPackageDirs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::vector< std::string,std::allocator< std::string > > *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::DOFSpatialForceArray *result = 0 ; - if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_setPackageDirs",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_setPackageDirs" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res2 = swig::asptr(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_setPackageDirs" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_setPackageDirs" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg2 = ptr; + } + (arg1)->setPackageDirs((std::vector< std::string,std::allocator< std::string > > const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + return 1; +} + + +int _wrap_Model_getLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("Model_getLinkName",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLinkName" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = ((iDynTree::Model const *)arg1)->getLinkName(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55121,63 +57986,70 @@ int _wrap_new_DOFSpatialForceArray__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialForceArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_DOFSpatialForceArray__SWIG_1(resc,resv,argc,argv); +int _wrap_Model_getLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + mxArray * _out; + iDynTree::LinkIndex result; + + if (!SWIG_check_num_args("Model_getLinkIndex",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_DOFSpatialForceArray__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getLinkIndex" "', argument " "2"" of type '" "std::string const &""'"); } - if (_v) { - return _wrap_new_DOFSpatialForceArray__SWIG_0(resc,resv,argc,argv); + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getLinkIndex" "', argument " "2"" of type '" "std::string const &""'"); } + arg2 = ptr; } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DOFSpatialForceArray'." - " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray(std::size_t)\n" - " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray()\n" - " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray(iDynTree::Model const &)\n"); + result = ((iDynTree::Model const *)arg1)->getLinkIndex((std::string const &)*arg2); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DOFSpatialForceArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; - std::size_t arg2 ; +int _wrap_Model_isValidLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DOFSpatialForceArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_isValidLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidLinkIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (bool)((iDynTree::Model const *)arg1)->isValidLinkIndex(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55185,33 +58057,63 @@ int _wrap_DOFSpatialForceArray_resize__SWIG_0(int resc, mxArray *resv[], int arg } -int _wrap_DOFSpatialForceArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getLink__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::LinkPtr result; - if (!SWIG_check_num_args("DOFSpatialForceArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::LinkPtr)(arg1)->getLink(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Model_getLink__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + iDynTree::LinkConstPtr result; + + if (!SWIG_check_num_args("Model_getLink",argc,2,2,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (iDynTree::LinkConstPtr)((iDynTree::Model const *)arg1)->getLink(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Link, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55219,105 +58121,240 @@ int _wrap_DOFSpatialForceArray_resize__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_DOFSpatialForceArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_getLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_DOFSpatialForceArray_resize__SWIG_1(resc,resv,argc,argv); + return _wrap_Model_getLink__SWIG_0(resc,resv,argc,argv); } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_DOFSpatialForceArray_resize__SWIG_0(resc,resv,argc,argv); + return _wrap_Model_getLink__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialForceArray_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_getLink'." " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialForceArray::resize(std::size_t const)\n" - " iDynTree::DOFSpatialForceArray::resize(iDynTree::Model const &)\n"); + " iDynTree::Model::getLink(iDynTree::LinkIndex const)\n" + " iDynTree::Model::getLink(iDynTree::LinkIndex const) const\n"); return 1; } -int _wrap_DOFSpatialForceArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_addLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + iDynTree::Link *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + int res2 = SWIG_OLDOBJ ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - bool result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("DOFSpatialForceArray_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_addLink",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Link, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addLink" "', argument " "3"" of type '" "iDynTree::Link const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addLink" "', argument " "3"" of type '" "iDynTree::Link const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Link * >(argp3); + result = (arg1)->addLink((std::string const &)*arg2,(iDynTree::Link const &)*arg3); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + return 1; +} + + +int _wrap_Model_getNrOfJoints(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + size_t result; + + if (!SWIG_check_num_args("Model_getNrOfJoints",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfJoints" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getNrOfJoints(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Model_getJointName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::JointIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("Model_getJointName",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJointName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJointName" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + } + arg2 = static_cast< iDynTree::JointIndex >(val2); + result = ((iDynTree::Model const *)arg1)->getJointName(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Model_getTotalMass(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + double result; + + if (!SWIG_check_num_args("Model_getTotalMass",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getTotalMass" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (double)((iDynTree::Model const *)arg1)->getTotalMass(); + _out = SWIG_From_double(static_cast< double >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Model_getJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + mxArray * _out; + iDynTree::JointIndex result; + + if (!SWIG_check_num_args("Model_getJointIndex",argc,2,2,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJointIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::DOFSpatialForceArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getJointIndex" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getJointIndex" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = ((iDynTree::Model const *)arg1)->getJointIndex((std::string const &)*arg2); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DOFSpatialForceArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; - size_t arg2 ; +int _wrap_Model_getJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::JointIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; + iDynTree::IJointPtr result; - if (!SWIG_check_num_args("DOFSpatialForceArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getJoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_paren" "', argument " "2"" of type '" "size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJoint" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::SpatialForceVector *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); + arg2 = static_cast< iDynTree::JointIndex >(val2); + result = (iDynTree::IJointPtr)(arg1)->getJoint(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55325,31 +58362,31 @@ int _wrap_DOFSpatialForceArray_paren__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_DOFSpatialForceArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; - size_t arg2 ; +int _wrap_Model_getJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::JointIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialForceVector *result = 0 ; + iDynTree::IJointConstPtr result; - if (!SWIG_check_num_args("DOFSpatialForceArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getJoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getJoint" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_paren" "', argument " "2"" of type '" "size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getJoint" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::SpatialForceVector *) &((iDynTree::DOFSpatialForceArray const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); + arg2 = static_cast< iDynTree::JointIndex >(val2); + result = (iDynTree::IJointConstPtr)((iDynTree::Model const *)arg1)->getJoint(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55357,66 +58394,71 @@ int _wrap_DOFSpatialForceArray_paren__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_DOFSpatialForceArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_getJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_DOFSpatialForceArray_paren__SWIG_0(resc,resv,argc,argv); + return _wrap_Model_getJoint__SWIG_0(resc,resv,argc,argv); } } } if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_DOFSpatialForceArray_paren__SWIG_1(resc,resv,argc,argv); + return _wrap_Model_getJoint__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialForceArray_paren'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_getJoint'." " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialForceArray::operator ()(size_t const)\n" - " iDynTree::DOFSpatialForceArray::operator ()(size_t const) const\n"); + " iDynTree::Model::getJoint(iDynTree::JointIndex const)\n" + " iDynTree::Model::getJoint(iDynTree::JointIndex const) const\n"); return 1; } -int _wrap_delete_DOFSpatialForceArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; +int _wrap_Model_isValidJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::JointIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_DOFSpatialForceArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_isValidJointIndex",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidJointIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + } + arg2 = static_cast< iDynTree::JointIndex >(val2); + result = (bool)((iDynTree::Model const *)arg1)->isValidJointIndex(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55424,23 +58466,33 @@ int _wrap_delete_DOFSpatialForceArray(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_DOFSpatialMotionArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Model_isLinkNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::DOFSpatialMotionArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_isLinkNameUsed",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "std::size_t""'"); - } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isLinkNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isLinkNameUsed" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + result = (bool)((iDynTree::Model const *)arg1)->isLinkNameUsed(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55448,16 +58500,33 @@ int _wrap_new_DOFSpatialMotionArray__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialMotionArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_isJointNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::DOFSpatialMotionArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,0,0,0)) { + if (!SWIG_check_num_args("Model_isJointNameUsed",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isJointNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isJointNameUsed" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + result = (bool)((iDynTree::Model const *)arg1)->isJointNameUsed(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55465,26 +58534,33 @@ int _wrap_new_DOFSpatialMotionArray__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialMotionArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_isFrameNameUsed(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string arg2 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::DOFSpatialMotionArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_isFrameNameUsed",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isFrameNameUsed" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "Model_isFrameNameUsed" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + result = (bool)((iDynTree::Model const *)arg1)->isFrameNameUsed(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55492,235 +58568,403 @@ int _wrap_new_DOFSpatialMotionArray__SWIG_2(int resc, mxArray *resv[], int argc, } -int _wrap_new_DOFSpatialMotionArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_DOFSpatialMotionArray__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_DOFSpatialMotionArray__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_DOFSpatialMotionArray__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DOFSpatialMotionArray'." - " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray(std::size_t)\n" - " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray()\n" - " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_DOFSpatialMotionArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; - std::size_t arg2 ; +int _wrap_Model_addJoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + iDynTree::IJointConstPtr arg3 = (iDynTree::IJointConstPtr) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + int res2 = SWIG_OLDOBJ ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("DOFSpatialMotionArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_addJoint",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJoint" "', argument " "3"" of type '" "iDynTree::IJointConstPtr""'"); + } + arg3 = reinterpret_cast< iDynTree::IJointConstPtr >(argp3); + result = (arg1)->addJoint((std::string const &)*arg2,arg3); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DOFSpatialMotionArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_addJoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + std::string *arg4 = 0 ; + iDynTree::IJointConstPtr arg5 = (iDynTree::IJointConstPtr) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + int res4 = SWIG_OLDOBJ ; + void *argp5 = 0 ; + int res5 = 0 ; mxArray * _out; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("DOFSpatialMotionArray_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_addJoint",argc,5,5,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJoint" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJoint" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + { + std::string *ptr = (std::string *)0; + res4 = SWIG_AsPtr_std_string(argv[3], &ptr); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addJoint" "', argument " "4"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJoint" "', argument " "4"" of type '" "std::string const &""'"); + } + arg4 = ptr; + } + res5 = SWIG_ConvertPtr(argv[4], &argp5,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_addJoint" "', argument " "5"" of type '" "iDynTree::IJointConstPtr""'"); + } + arg5 = reinterpret_cast< iDynTree::IJointConstPtr >(argp5); + result = (arg1)->addJoint((std::string const &)*arg2,(std::string const &)*arg3,(std::string const &)*arg4,arg5); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_DOFSpatialMotionArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_Model_addJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_DOFSpatialMotionArray_resize__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__IJoint, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Model_addJoint__SWIG_0(resc,resv,argc,argv); + } } } } - if (argc == 2) { + if (argc == 5) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_DOFSpatialMotionArray_resize__SWIG_0(resc,resv,argc,argv); + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__IJoint, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Model_addJoint__SWIG_1(resc,resv,argc,argv); + } + } + } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialMotionArray_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_addJoint'." " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialMotionArray::resize(std::size_t const)\n" - " iDynTree::DOFSpatialMotionArray::resize(iDynTree::Model const &)\n"); + " iDynTree::Model::addJoint(std::string const &,iDynTree::IJointConstPtr)\n" + " iDynTree::Model::addJoint(std::string const &,std::string const &,std::string const &,iDynTree::IJointConstPtr)\n"); return 1; } -int _wrap_DOFSpatialMotionArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_addJointAndLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + iDynTree::IJointConstPtr arg4 = (iDynTree::IJointConstPtr) 0 ; + std::string *arg5 = 0 ; + iDynTree::Link *arg6 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + void *argp4 = 0 ; + int res4 = 0 ; + int res5 = SWIG_OLDOBJ ; + void *argp6 = 0 ; + int res6 = 0 ; mxArray * _out; - bool result; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("DOFSpatialMotionArray_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_addJointAndLink",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addJointAndLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addJointAndLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addJointAndLink" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::DOFSpatialMotionArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + res4 = SWIG_ConvertPtr(argv[3], &argp4,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addJointAndLink" "', argument " "4"" of type '" "iDynTree::IJointConstPtr""'"); + } + arg4 = reinterpret_cast< iDynTree::IJointConstPtr >(argp4); + { + std::string *ptr = (std::string *)0; + res5 = SWIG_AsPtr_std_string(argv[4], &ptr); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_addJointAndLink" "', argument " "5"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "5"" of type '" "std::string const &""'"); + } + arg5 = ptr; + } + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__Link, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "Model_addJointAndLink" "', argument " "6"" of type '" "iDynTree::Link &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addJointAndLink" "', argument " "6"" of type '" "iDynTree::Link &""'"); + } + arg6 = reinterpret_cast< iDynTree::Link * >(argp6); + result = (arg1)->addJointAndLink((std::string const &)*arg2,(std::string const &)*arg3,arg4,(std::string const &)*arg5,*arg6); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; return 1; } -int _wrap_DOFSpatialMotionArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; - size_t arg2 ; +int _wrap_Model_insertLinkToExistingJointAndAddJointForDisplacedLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + iDynTree::Transform *arg4 = 0 ; + std::string *arg5 = 0 ; + iDynTree::IJointConstPtr arg6 = (iDynTree::IJointConstPtr) 0 ; + std::string *arg7 = 0 ; + iDynTree::Link *arg8 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + void *argp4 ; + int res4 = 0 ; + int res5 = SWIG_OLDOBJ ; + void *argp6 = 0 ; + int res6 = 0 ; + int res7 = SWIG_OLDOBJ ; + void *argp8 = 0 ; + int res8 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; + iDynTree::JointIndex result; - if (!SWIG_check_num_args("DOFSpatialMotionArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_insertLinkToExistingJointAndAddJointForDisplacedLink",argc,8,8,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_paren" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::SpatialMotionVector *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; + } + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "4"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "4"" of type '" "iDynTree::Transform const &""'"); + } + arg4 = reinterpret_cast< iDynTree::Transform * >(argp4); + { + std::string *ptr = (std::string *)0; + res5 = SWIG_AsPtr_std_string(argv[4], &ptr); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "5"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "5"" of type '" "std::string const &""'"); + } + arg5 = ptr; + } + res6 = SWIG_ConvertPtr(argv[5], &argp6,SWIGTYPE_p_iDynTree__IJoint, 0 | 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "6"" of type '" "iDynTree::IJointConstPtr""'"); + } + arg6 = reinterpret_cast< iDynTree::IJointConstPtr >(argp6); + { + std::string *ptr = (std::string *)0; + res7 = SWIG_AsPtr_std_string(argv[6], &ptr); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "7"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "7"" of type '" "std::string const &""'"); + } + arg7 = ptr; + } + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__Link, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "8"" of type '" "iDynTree::Link &""'"); + } + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_insertLinkToExistingJointAndAddJointForDisplacedLink" "', argument " "8"" of type '" "iDynTree::Link &""'"); + } + arg8 = reinterpret_cast< iDynTree::Link * >(argp8); + result = (arg1)->insertLinkToExistingJointAndAddJointForDisplacedLink((std::string const &)*arg2,(std::string const &)*arg3,(iDynTree::Transform const &)*arg4,(std::string const &)*arg5,arg6,(std::string const &)*arg7,*arg8); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + if (SWIG_IsNewObj(res7)) delete arg7; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + if (SWIG_IsNewObj(res7)) delete arg7; return 1; } -int _wrap_DOFSpatialMotionArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; - size_t arg2 ; +int _wrap_Model_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::SpatialMotionVector *result = 0 ; + size_t result; - if (!SWIG_check_num_args("DOFSpatialMotionArray_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getNrOfPosCoords",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_paren" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::SpatialMotionVector *) &((iDynTree::DOFSpatialMotionArray const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getNrOfPosCoords(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55728,66 +58972,23 @@ int _wrap_DOFSpatialMotionArray_paren__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_DOFSpatialMotionArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_DOFSpatialMotionArray_paren__SWIG_0(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_DOFSpatialMotionArray_paren__SWIG_1(resc,resv,argc,argv); - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialMotionArray_paren'." - " Possible C/C++ prototypes are:\n" - " iDynTree::DOFSpatialMotionArray::operator ()(size_t const)\n" - " iDynTree::DOFSpatialMotionArray::operator ()(size_t const) const\n"); - return 1; -} - - -int _wrap_delete_DOFSpatialMotionArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; +int _wrap_Model_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + size_t result; - int is_owned; - if (!SWIG_check_num_args("delete_DOFSpatialMotionArray",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getNrOfDOFs",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); - } - arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55795,40 +58996,23 @@ int _wrap_delete_DOFSpatialMotionArray(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_new_FrameFreeFloatingJacobian__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Model_getNrOfFrames(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::FrameFreeFloatingJacobian *result = 0 ; + size_t result; - if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getNrOfFrames",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "size_t""'"); - } - arg1 = static_cast< size_t >(val1); - result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FrameFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::FrameFreeFloatingJacobian *result = 0 ; - - if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,0,0,0)) { - SWIG_fail; + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfFrames" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - (void)argv; - result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getNrOfFrames(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55836,93 +59020,99 @@ int _wrap_new_FrameFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], int a } -int _wrap_new_FrameFreeFloatingJacobian__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_addAdditionalFrameToLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + iDynTree::Transform arg4 ; + void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; - iDynTree::FrameFreeFloatingJacobian *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_addAdditionalFrameToLink",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_addAdditionalFrameToLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FrameFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_FrameFreeFloatingJacobian__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_FrameFreeFloatingJacobian__SWIG_2(resc,resv,argc,argv); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_addAdditionalFrameToLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "2"" of type '" "std::string const &""'"); } + arg2 = ptr; } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_addAdditionalFrameToLink" "', argument " "3"" of type '" "std::string const &""'"); } - if (_v) { - return _wrap_new_FrameFreeFloatingJacobian__SWIG_0(resc,resv,argc,argv); + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "3"" of type '" "std::string const &""'"); } + arg3 = ptr; } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FrameFreeFloatingJacobian'." - " Possible C/C++ prototypes are:\n" - " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian(size_t)\n" - " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian()\n" - " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian(iDynTree::Model const &)\n"); + { + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "Model_addAdditionalFrameToLink" "', argument " "4"" of type '" "iDynTree::Transform""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_addAdditionalFrameToLink" "', argument " "4"" of type '" "iDynTree::Transform""'"); + } else { + arg4 = *(reinterpret_cast< iDynTree::Transform * >(argp4)); + } + } + result = (bool)(arg1)->addAdditionalFrameToLink((std::string const &)*arg2,(std::string const &)*arg3,arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_FrameFreeFloatingJacobian_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getFrameName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::FrameIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("FrameFreeFloatingJacobian_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getFrameName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian *""'"); - } - arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameName" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameName" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); + } + arg2 = static_cast< iDynTree::FrameIndex >(val2); + result = ((iDynTree::Model const *)arg1)->getFrameName(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55930,61 +59120,70 @@ int _wrap_FrameFreeFloatingJacobian_resize(int resc, mxArray *resv[], int argc, } -int _wrap_FrameFreeFloatingJacobian_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getFrameIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + iDynTree::FrameIndex result; - if (!SWIG_check_num_args("FrameFreeFloatingJacobian_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getFrameIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian const *""'"); - } - arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getFrameIndex" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getFrameIndex" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::FrameFreeFloatingJacobian const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + result = ((iDynTree::Model const *)arg1)->getFrameIndex((std::string const &)*arg2); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_delete_FrameFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; +int _wrap_Model_isValidFrameIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::FrameIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_FrameFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_isValidFrameIndex",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian *""'"); - } - arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValidFrameIndex" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_isValidFrameIndex" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); + } + arg2 = static_cast< iDynTree::FrameIndex >(val2); + result = (bool)((iDynTree::Model const *)arg1)->isValidFrameIndex(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -55992,23 +59191,31 @@ int _wrap_delete_FrameFreeFloatingJacobian(int resc, mxArray *resv[], int argc, } -int _wrap_new_MomentumFreeFloatingJacobian__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Model_getFrameTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::FrameIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::MomentumFreeFloatingJacobian *result = 0 ; + iDynTree::Transform result; - if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getFrameTransform",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "size_t""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameTransform" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameTransform" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); } - arg1 = static_cast< size_t >(val1); - result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); + arg2 = static_cast< iDynTree::FrameIndex >(val2); + result = ((iDynTree::Model const *)arg1)->getFrameTransform(arg2); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56016,16 +59223,31 @@ int _wrap_new_MomentumFreeFloatingJacobian__SWIG_0(int resc, mxArray *resv[], in } -int _wrap_new_MomentumFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_getFrameLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::FrameIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::MomentumFreeFloatingJacobian *result = 0 ; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,0,0,0)) { + if (!SWIG_check_num_args("Model_getFrameLink",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getFrameLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getFrameLink" "', argument " "2"" of type '" "iDynTree::FrameIndex""'"); + } + arg2 = static_cast< iDynTree::FrameIndex >(val2); + result = ((iDynTree::Model const *)arg1)->getFrameLink(arg2); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56033,26 +59255,42 @@ int _wrap_new_MomentumFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], in } -int _wrap_new_MomentumFreeFloatingJacobian__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_getLinkAdditionalFrames(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; + std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > *arg3 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::MomentumFreeFloatingJacobian *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getLinkAdditionalFrames",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getLinkAdditionalFrames" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getLinkAdditionalFrames" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "Model_getLinkAdditionalFrames" "', argument " "3"" of type '" "std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getLinkAdditionalFrames" "', argument " "3"" of type '" "std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > * >(argp3); + result = (bool)((iDynTree::Model const *)arg1)->getLinkAdditionalFrames(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56060,66 +59298,31 @@ int _wrap_new_MomentumFreeFloatingJacobian__SWIG_2(int resc, mxArray *resv[], in } -int _wrap_new_MomentumFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_MomentumFreeFloatingJacobian__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_MomentumFreeFloatingJacobian__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_MomentumFreeFloatingJacobian__SWIG_0(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_MomentumFreeFloatingJacobian'." - " Possible C/C++ prototypes are:\n" - " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian(size_t)\n" - " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian()\n" - " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_MomentumFreeFloatingJacobian_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getNrOfNeighbors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + unsigned int result; - if (!SWIG_check_num_args("MomentumFreeFloatingJacobian_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getNrOfNeighbors",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian *""'"); - } - arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNrOfNeighbors" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getNrOfNeighbors" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (unsigned int)((iDynTree::Model const *)arg1)->getNrOfNeighbors(arg2); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56127,34 +59330,39 @@ int _wrap_MomentumFreeFloatingJacobian_resize(int resc, mxArray *resv[], int arg } -int _wrap_MomentumFreeFloatingJacobian_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getNeighbor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; + unsigned int arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + unsigned int val3 ; + int ecode3 = 0 ; mxArray * _out; - bool result; + iDynTree::Neighbor result; - if (!SWIG_check_num_args("MomentumFreeFloatingJacobian_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getNeighbor",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian const *""'"); - } - arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getNeighbor" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::MomentumFreeFloatingJacobian const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_getNeighbor" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_unsigned_SS_int(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Model_getNeighbor" "', argument " "3"" of type '" "unsigned int""'"); + } + arg3 = static_cast< unsigned int >(val3); + result = ((iDynTree::Model const *)arg1)->getNeighbor(arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Neighbor(static_cast< const iDynTree::Neighbor& >(result))), SWIGTYPE_p_iDynTree__Neighbor, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56162,26 +59370,31 @@ int _wrap_MomentumFreeFloatingJacobian_isConsistent(int resc, mxArray *resv[], i } -int _wrap_delete_MomentumFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; +int _wrap_Model_setDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_MomentumFreeFloatingJacobian",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_setDefaultBaseLink",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian *""'"); - } - arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_setDefaultBaseLink" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "Model_setDefaultBaseLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (bool)(arg1)->setDefaultBaseLink(arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56189,23 +59402,23 @@ int _wrap_delete_MomentumFreeFloatingJacobian(int resc, mxArray *resv[], int arg } -int _wrap_new_FreeFloatingMassMatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - size_t arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_Model_getDefaultBaseLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::FreeFloatingMassMatrix *result = 0 ; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_getDefaultBaseLink",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "size_t""'"); - } - arg1 = static_cast< size_t >(val1); - result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getDefaultBaseLink" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->getDefaultBaseLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56213,16 +59426,34 @@ int _wrap_new_FreeFloatingMassMatrix__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_new_FreeFloatingMassMatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_computeFullTreeTraversal__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::Traversal *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::FreeFloatingMassMatrix *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,0,0,0)) { + if (!SWIG_check_num_args("Model_computeFullTreeTraversal",argc,2,2,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_computeFullTreeTraversal" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + result = (bool)((iDynTree::Model const *)arg1)->computeFullTreeTraversal(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56230,26 +59461,42 @@ int _wrap_new_FreeFloatingMassMatrix__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_new_FreeFloatingMassMatrix__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_computeFullTreeTraversal__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::LinkIndex arg3 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - iDynTree::FreeFloatingMassMatrix *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_computeFullTreeTraversal",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_computeFullTreeTraversal" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_computeFullTreeTraversal" "', argument " "2"" of type '" "iDynTree::Traversal &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "Model_computeFullTreeTraversal" "', argument " "3"" of type '" "iDynTree::LinkIndex""'"); + } + arg3 = static_cast< iDynTree::LinkIndex >(val3); + result = (bool)((iDynTree::Model const *)arg1)->computeFullTreeTraversal(*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56257,66 +59504,78 @@ int _wrap_new_FreeFloatingMassMatrix__SWIG_2(int resc, mxArray *resv[], int argc } -int _wrap_new_FreeFloatingMassMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_FreeFloatingMassMatrix__SWIG_1(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_Model_computeFullTreeTraversal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingMassMatrix__SWIG_2(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Model_computeFullTreeTraversal__SWIG_0(resc,resv,argc,argv); + } } } - if (argc == 1) { + if (argc == 3) { int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingMassMatrix__SWIG_0(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_Model_computeFullTreeTraversal__SWIG_1(resc,resv,argc,argv); + } + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingMassMatrix'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_computeFullTreeTraversal'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix(size_t)\n" - " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix()\n" - " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix(iDynTree::Model const &)\n"); + " iDynTree::Model::computeFullTreeTraversal(iDynTree::Traversal &) const\n" + " iDynTree::Model::computeFullTreeTraversal(iDynTree::Traversal &,iDynTree::LinkIndex const) const\n"); return 1; } -int _wrap_FreeFloatingMassMatrix_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingMassMatrix *arg1 = (iDynTree::FreeFloatingMassMatrix *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_Model_getInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("FreeFloatingMassMatrix_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("Model_getInertialParameters",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingMassMatrix_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingMassMatrix *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_getInertialParameters" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingMassMatrix_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_getInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingMassMatrix_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_getInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + result = (bool)((iDynTree::Model const *)arg1)->getInertialParameters(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56324,26 +59583,34 @@ int _wrap_FreeFloatingMassMatrix_resize(int resc, mxArray *resv[], int argc, mxA } -int _wrap_delete_FreeFloatingMassMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingMassMatrix *arg1 = (iDynTree::FreeFloatingMassMatrix *) 0 ; +int _wrap_Model_updateInertialParameters(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_FreeFloatingMassMatrix",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_updateInertialParameters",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::FreeFloatingMassMatrix *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_updateInertialParameters" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Model_updateInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); } - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Model_updateInertialParameters" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); + } + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + result = (bool)(arg1)->updateInertialParameters((iDynTree::VectorDynSize const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56351,16 +59618,23 @@ int _wrap_delete_FreeFloatingMassMatrix(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_FreeFloatingPos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_visualSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::FreeFloatingPos *result = 0 ; + iDynTree::ModelSolidShapes *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingPos",argc,0,0,0)) { + if (!SWIG_check_num_args("Model_visualSolidShapes",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::FreeFloatingPos *)new iDynTree::FreeFloatingPos(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingPos, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_visualSolidShapes" "', argument " "1"" of type '" "iDynTree::Model *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::ModelSolidShapes *) &(arg1)->visualSolidShapes(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56368,26 +59642,23 @@ int _wrap_new_FreeFloatingPos__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_FreeFloatingPos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_Model_visualSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::FreeFloatingPos *result = 0 ; + iDynTree::ModelSolidShapes *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingPos",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_visualSolidShapes",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_visualSolidShapes" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FreeFloatingPos *)new iDynTree::FreeFloatingPos((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingPos, 1 | 0 ); + result = (iDynTree::ModelSolidShapes *) &((iDynTree::Model const *)arg1)->visualSolidShapes(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56395,9 +59666,15 @@ int _wrap_new_FreeFloatingPos__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_FreeFloatingPos__SWIG_0(resc,resv,argc,argv); +int _wrap_Model_visualSolidShapes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_Model_visualSolidShapes__SWIG_0(resc,resv,argc,argv); + } } if (argc == 1) { int _v; @@ -56405,93 +59682,35 @@ int _wrap_new_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *argv int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingPos__SWIG_1(resc,resv,argc,argv); + return _wrap_Model_visualSolidShapes__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingPos'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_visualSolidShapes'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingPos::FreeFloatingPos()\n" - " iDynTree::FreeFloatingPos::FreeFloatingPos(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_FreeFloatingPos_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("FreeFloatingPos_resize",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingPos_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingPos_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_FreeFloatingPos_worldBasePos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Transform *result = 0 ; - - if (!SWIG_check_num_args("FreeFloatingPos_worldBasePos",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_worldBasePos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - result = (iDynTree::Transform *) &(arg1)->worldBasePos(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::Model::visualSolidShapes()\n" + " iDynTree::Model::visualSolidShapes() const\n"); return 1; } -int _wrap_FreeFloatingPos_jointPos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; +int _wrap_Model_collisionSolidShapes__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointPosDoubleArray *result = 0 ; + iDynTree::ModelSolidShapes *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingPos_jointPos",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_collisionSolidShapes",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_jointPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_collisionSolidShapes" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - result = (iDynTree::JointPosDoubleArray *) &(arg1)->jointPos(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::ModelSolidShapes *) &(arg1)->collisionSolidShapes(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56499,23 +59718,23 @@ int _wrap_FreeFloatingPos_jointPos__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingPos_worldBasePos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; +int _wrap_Model_collisionSolidShapes__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::ModelSolidShapes *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingPos_worldBasePos",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_collisionSolidShapes",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_worldBasePos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_collisionSolidShapes" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - result = (iDynTree::Transform *) &((iDynTree::FreeFloatingPos const *)arg1)->worldBasePos(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::ModelSolidShapes *) &((iDynTree::Model const *)arg1)->collisionSolidShapes(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ModelSolidShapes, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56523,51 +59742,51 @@ int _wrap_FreeFloatingPos_worldBasePos__SWIG_1(int resc, mxArray *resv[], int ar } -int _wrap_FreeFloatingPos_worldBasePos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_collisionSolidShapes(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingPos_worldBasePos__SWIG_0(resc,resv,argc,argv); + return _wrap_Model_collisionSolidShapes__SWIG_0(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingPos_worldBasePos__SWIG_1(resc,resv,argc,argv); + return _wrap_Model_collisionSolidShapes__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingPos_worldBasePos'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_collisionSolidShapes'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingPos::worldBasePos()\n" - " iDynTree::FreeFloatingPos::worldBasePos() const\n"); + " iDynTree::Model::collisionSolidShapes()\n" + " iDynTree::Model::collisionSolidShapes() const\n"); return 1; } -int _wrap_FreeFloatingPos_jointPos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; +int _wrap_Model_sensors__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointPosDoubleArray *result = 0 ; + iDynTree::SensorsList *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingPos_jointPos",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_sensors",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_jointPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_sensors" "', argument " "1"" of type '" "iDynTree::Model *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - result = (iDynTree::JointPosDoubleArray *) &((iDynTree::FreeFloatingPos const *)arg1)->jointPos(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::SensorsList *) &(arg1)->sensors(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56575,51 +59794,75 @@ int _wrap_FreeFloatingPos_jointPos__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingPos_jointPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_Model_sensors__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::SensorsList *result = 0 ; + + if (!SWIG_check_num_args("Model_sensors",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_sensors" "', argument " "1"" of type '" "iDynTree::Model const *""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::SensorsList *) &((iDynTree::Model const *)arg1)->sensors(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_Model_sensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingPos_jointPos__SWIG_0(resc,resv,argc,argv); + return _wrap_Model_sensors__SWIG_0(resc,resv,argc,argv); } } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingPos_jointPos__SWIG_1(resc,resv,argc,argv); + return _wrap_Model_sensors__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingPos_jointPos'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'Model_sensors'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingPos::jointPos()\n" - " iDynTree::FreeFloatingPos::jointPos() const\n"); + " iDynTree::Model::sensors()\n" + " iDynTree::Model::sensors() const\n"); return 1; } -int _wrap_FreeFloatingPos_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; +int _wrap_Model_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - unsigned int result; + std::string result; - if (!SWIG_check_num_args("FreeFloatingPos_getNrOfPosCoords",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_toString",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_toString" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - result = (unsigned int)((iDynTree::FreeFloatingPos const *)arg1)->getNrOfPosCoords(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = ((iDynTree::Model const *)arg1)->toString(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56627,26 +59870,47 @@ int _wrap_FreeFloatingPos_getNrOfPosCoords(int resc, mxArray *resv[], int argc, } -int _wrap_delete_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; +int _wrap_Model_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = (iDynTree::Model *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_FreeFloatingPos",argc,1,1,0)) { + if (!SWIG_check_num_args("Model_isValid",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Model, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Model_isValid" "', argument " "1"" of type '" "iDynTree::Model const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (bool)((iDynTree::Model const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_JointPosDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + iDynTree::JointPosDoubleArray *result = 0 ; + + if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,1,1,0)) { + SWIG_fail; } - _out = (mxArray*)0; + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56654,16 +59918,16 @@ int _wrap_delete_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_JointPosDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::FreeFloatingGeneralizedTorques *result = 0 ; + iDynTree::JointPosDoubleArray *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingGeneralizedTorques",argc,0,0,0)) { + if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::FreeFloatingGeneralizedTorques *)new iDynTree::FreeFloatingGeneralizedTorques(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 1 | 0 ); + result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56671,26 +59935,26 @@ int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_0(int resc, mxArray *resv[], } -int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_JointPosDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::FreeFloatingGeneralizedTorques *result = 0 ; + iDynTree::JointPosDoubleArray *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingGeneralizedTorques",argc,1,1,0)) { + if (!SWIG_check_num_args("new_JointPosDoubleArray",argc,1,1,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FreeFloatingGeneralizedTorques *)new iDynTree::FreeFloatingGeneralizedTorques((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 1 | 0 ); + result = (iDynTree::JointPosDoubleArray *)new iDynTree::JointPosDoubleArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56698,9 +59962,9 @@ int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_1(int resc, mxArray *resv[], } -int _wrap_new_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_JointPosDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_FreeFloatingGeneralizedTorques__SWIG_0(resc,resv,argc,argv); + return _wrap_new_JointPosDoubleArray__SWIG_1(resc,resv,argc,argv); } if (argc == 1) { int _v; @@ -56708,20 +59972,62 @@ int _wrap_new_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int argc int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingGeneralizedTorques__SWIG_1(resc,resv,argc,argv); + return _wrap_new_JointPosDoubleArray__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_JointPosDoubleArray__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingGeneralizedTorques'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_JointPosDoubleArray'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingGeneralizedTorques::FreeFloatingGeneralizedTorques()\n" - " iDynTree::FreeFloatingGeneralizedTorques::FreeFloatingGeneralizedTorques(iDynTree::Model const &)\n"); + " iDynTree::JointPosDoubleArray::JointPosDoubleArray(std::size_t)\n" + " iDynTree::JointPosDoubleArray::JointPosDoubleArray()\n" + " iDynTree::JointPosDoubleArray::JointPosDoubleArray(iDynTree::Model const &)\n"); return 1; } -int _wrap_FreeFloatingGeneralizedTorques_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; +int _wrap_JointPosDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("JointPosDoubleArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_JointPosDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -56729,20 +60035,20 @@ int _wrap_FreeFloatingGeneralizedTorques_resize(int resc, mxArray *resv[], int a int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("JointPosDoubleArray_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointPosDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); (arg1)->resize((iDynTree::Model const &)*arg2); @@ -56754,23 +60060,73 @@ int _wrap_FreeFloatingGeneralizedTorques_resize(int resc, mxArray *resv[], int a } -int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; +int _wrap_JointPosDoubleArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_JointPosDoubleArray_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_JointPosDoubleArray_resize__SWIG_0(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'JointPosDoubleArray_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::JointPosDoubleArray::resize(std::size_t)\n" + " iDynTree::JointPosDoubleArray::resize(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_JointPosDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + bool result; - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_baseWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("JointPosDoubleArray_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_baseWrench" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointPosDoubleArray_isConsistent" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - result = (iDynTree::Wrench *) &(arg1)->baseWrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointPosDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointPosDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::JointPosDoubleArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56778,23 +60134,26 @@ int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_0(int resc, mxArray *r } -int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; +int _wrap_delete_JointPosDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointPosDoubleArray *arg1 = (iDynTree::JointPosDoubleArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_jointTorques",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_JointPosDoubleArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointPosDoubleArray, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_jointTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointPosDoubleArray" "', argument " "1"" of type '" "iDynTree::JointPosDoubleArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointTorques(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56802,23 +60161,23 @@ int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_0(int resc, mxArray } -int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_JointDOFsDoubleArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_baseWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_baseWrench" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - result = (iDynTree::Wrench *) &((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->baseWrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56826,51 +60185,43 @@ int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_1(int resc, mxArray *r } -int _wrap_FreeFloatingGeneralizedTorques_baseWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_0(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_new_JointDOFsDoubleArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::JointDOFsDoubleArray *result = 0 ; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingGeneralizedTorques_baseWrench'." - " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingGeneralizedTorques::baseWrench()\n" - " iDynTree::FreeFloatingGeneralizedTorques::baseWrench() const\n"); + if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; - void *argp1 = 0 ; +int _wrap_new_JointDOFsDoubleArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_jointTorques",argc,1,1,0)) { + if (!SWIG_check_num_args("new_JointDOFsDoubleArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_jointTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->jointTorques(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *)new iDynTree::JointDOFsDoubleArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -56878,77 +60229,62 @@ int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_1(int resc, mxArray } -int _wrap_FreeFloatingGeneralizedTorques_jointTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_JointDOFsDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_JointDOFsDoubleArray__SWIG_1(resc,resv,argc,argv); + } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_0(resc,resv,argc,argv); + return _wrap_new_JointDOFsDoubleArray__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_1(resc,resv,argc,argv); + return _wrap_new_JointDOFsDoubleArray__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingGeneralizedTorques_jointTorques'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_JointDOFsDoubleArray'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingGeneralizedTorques::jointTorques()\n" - " iDynTree::FreeFloatingGeneralizedTorques::jointTorques() const\n"); - return 1; -} - - -int _wrap_FreeFloatingGeneralizedTorques_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - unsigned int result; - - if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_getNrOfDOFs",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - result = (unsigned int)((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray(std::size_t)\n" + " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray()\n" + " iDynTree::JointDOFsDoubleArray::JointDOFsDoubleArray(iDynTree::Model const &)\n"); return 1; } -int _wrap_delete_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; +int _wrap_JointDOFsDoubleArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_FreeFloatingGeneralizedTorques",argc,1,1,0)) { + if (!SWIG_check_num_args("JointDOFsDoubleArray_resize",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); } + arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -56957,43 +60293,33 @@ int _wrap_delete_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int a } -int _wrap_new_FreeFloatingVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::FreeFloatingVel *result = 0 ; - - if (!SWIG_check_num_args("new_FreeFloatingVel",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::FreeFloatingVel *)new iDynTree::FreeFloatingVel(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingVel, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FreeFloatingVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_JointDOFsDoubleArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::FreeFloatingVel *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingVel",argc,1,1,0)) { + if (!SWIG_check_num_args("JointDOFsDoubleArray_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_resize" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FreeFloatingVel *)new iDynTree::FreeFloatingVel((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingVel, 1 | 0 ); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointDOFsDoubleArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57001,55 +60327,73 @@ int _wrap_new_FreeFloatingVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_FreeFloatingVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_FreeFloatingVel__SWIG_0(resc,resv,argc,argv); +int _wrap_JointDOFsDoubleArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_JointDOFsDoubleArray_resize__SWIG_1(resc,resv,argc,argv); + } + } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingVel__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_JointDOFsDoubleArray_resize__SWIG_0(resc,resv,argc,argv); + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingVel'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'JointDOFsDoubleArray_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingVel::FreeFloatingVel()\n" - " iDynTree::FreeFloatingVel::FreeFloatingVel(iDynTree::Model const &)\n"); + " iDynTree::JointDOFsDoubleArray::resize(std::size_t)\n" + " iDynTree::JointDOFsDoubleArray::resize(iDynTree::Model const &)\n"); return 1; } -int _wrap_FreeFloatingVel_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; +int _wrap_JointDOFsDoubleArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("FreeFloatingVel_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("JointDOFsDoubleArray_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingVel_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingVel_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointDOFsDoubleArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + result = (bool)((iDynTree::JointDOFsDoubleArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57057,23 +60401,26 @@ int _wrap_FreeFloatingVel_resize(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_FreeFloatingVel_baseVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; +int _wrap_delete_JointDOFsDoubleArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::JointDOFsDoubleArray *arg1 = (iDynTree::JointDOFsDoubleArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingVel_baseVel",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_JointDOFsDoubleArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_baseVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointDOFsDoubleArray" "', argument " "1"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - result = (iDynTree::Twist *) &(arg1)->baseVel(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57081,23 +60428,40 @@ int _wrap_FreeFloatingVel_baseVel__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_FreeFloatingVel_jointVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_DOFSpatialForceArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + iDynTree::DOFSpatialForceArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingVel_jointVel",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_jointVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_DOFSpatialForceArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::DOFSpatialForceArray *result = 0 ; + + if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,0,0,0)) { + SWIG_fail; } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointVel(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + (void)argv; + result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57105,23 +60469,26 @@ int _wrap_FreeFloatingVel_jointVel__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingVel_baseVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; - void *argp1 = 0 ; +int _wrap_new_DOFSpatialForceArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::Twist *result = 0 ; + iDynTree::DOFSpatialForceArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingVel_baseVel",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DOFSpatialForceArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_baseVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - result = (iDynTree::Twist *) &((iDynTree::FreeFloatingVel const *)arg1)->baseVel(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::DOFSpatialForceArray *)new iDynTree::DOFSpatialForceArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57129,51 +60496,63 @@ int _wrap_FreeFloatingVel_baseVel__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_FreeFloatingVel_baseVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_DOFSpatialForceArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_DOFSpatialForceArray__SWIG_1(resc,resv,argc,argv); + } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingVel_baseVel__SWIG_0(resc,resv,argc,argv); + return _wrap_new_DOFSpatialForceArray__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_FreeFloatingVel_baseVel__SWIG_1(resc,resv,argc,argv); + return _wrap_new_DOFSpatialForceArray__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingVel_baseVel'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DOFSpatialForceArray'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingVel::baseVel()\n" - " iDynTree::FreeFloatingVel::baseVel() const\n"); + " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray(std::size_t)\n" + " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray()\n" + " iDynTree::DOFSpatialForceArray::DOFSpatialForceArray(iDynTree::Model const &)\n"); return 1; } -int _wrap_FreeFloatingVel_jointVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; +int _wrap_DOFSpatialForceArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingVel_jointVel",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialForceArray_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_jointVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingVel const *)arg1)->jointVel(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57181,51 +60560,107 @@ int _wrap_FreeFloatingVel_jointVel__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingVel_jointVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { +int _wrap_DOFSpatialForceArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("DOFSpatialForceArray_resize",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); + } + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialForceArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_DOFSpatialForceArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingVel_jointVel__SWIG_0(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_DOFSpatialForceArray_resize__SWIG_1(resc,resv,argc,argv); + } } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingVel_jointVel__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialForceArray_resize__SWIG_0(resc,resv,argc,argv); + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingVel_jointVel'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialForceArray_resize'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingVel::jointVel()\n" - " iDynTree::FreeFloatingVel::jointVel() const\n"); + " iDynTree::DOFSpatialForceArray::resize(std::size_t const)\n" + " iDynTree::DOFSpatialForceArray::resize(iDynTree::Model const &)\n"); return 1; } -int _wrap_FreeFloatingVel_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; +int _wrap_DOFSpatialForceArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - unsigned int result; + bool result; - if (!SWIG_check_num_args("FreeFloatingVel_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialForceArray_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - result = (unsigned int)((iDynTree::FreeFloatingVel const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialForceArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::DOFSpatialForceArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57233,43 +60668,31 @@ int _wrap_FreeFloatingVel_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_delete_FreeFloatingVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; +int _wrap_DOFSpatialForceArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::SpatialForceVector *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_FreeFloatingVel",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialForceArray_paren",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_FreeFloatingAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::FreeFloatingAcc *result = 0 ; - - if (!SWIG_check_num_args("new_FreeFloatingAcc",argc,0,0,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); } - (void)argv; - result = (iDynTree::FreeFloatingAcc *)new iDynTree::FreeFloatingAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingAcc, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::SpatialForceVector *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57277,26 +60700,31 @@ int _wrap_new_FreeFloatingAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_FreeFloatingAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_DOFSpatialForceArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; + size_t arg2 ; + void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::FreeFloatingAcc *result = 0 ; + iDynTree::SpatialForceVector *result = 0 ; - if (!SWIG_check_num_args("new_FreeFloatingAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialForceArray_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialForceArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::FreeFloatingAcc *)new iDynTree::FreeFloatingAcc((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingAcc, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialForceArray_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::SpatialForceVector *) &((iDynTree::DOFSpatialForceArray const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialForceVector, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57304,54 +60732,65 @@ int _wrap_new_FreeFloatingAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_FreeFloatingAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_FreeFloatingAcc__SWIG_0(resc,resv,argc,argv); +int _wrap_DOFSpatialForceArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialForceArray_paren__SWIG_0(resc,resv,argc,argv); + } + } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_FreeFloatingAcc__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialForceArray_paren__SWIG_1(resc,resv,argc,argv); + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingAcc'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialForceArray_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingAcc::FreeFloatingAcc()\n" - " iDynTree::FreeFloatingAcc::FreeFloatingAcc(iDynTree::Model const &)\n"); + " iDynTree::DOFSpatialForceArray::operator ()(size_t const)\n" + " iDynTree::DOFSpatialForceArray::operator ()(size_t const) const\n"); return 1; } -int _wrap_FreeFloatingAcc_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_delete_DOFSpatialForceArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialForceArray *arg1 = (iDynTree::DOFSpatialForceArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("FreeFloatingAcc_resize",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_DOFSpatialForceArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingAcc_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DOFSpatialForceArray" "', argument " "1"" of type '" "iDynTree::DOFSpatialForceArray *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingAcc_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -57360,47 +60799,23 @@ int _wrap_FreeFloatingAcc_resize(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_FreeFloatingAcc_baseAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; - - if (!SWIG_check_num_args("FreeFloatingAcc_baseAcc",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_baseAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - result = (iDynTree::SpatialAcc *) &(arg1)->baseAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_FreeFloatingAcc_jointAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_DOFSpatialMotionArray__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + iDynTree::DOFSpatialMotionArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingAcc_jointAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_jointAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "std::size_t""'"); + } + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57408,23 +60823,16 @@ int _wrap_FreeFloatingAcc_jointAcc__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingAcc_baseAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_DOFSpatialMotionArray__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SpatialAcc *result = 0 ; + iDynTree::DOFSpatialMotionArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingAcc_baseAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_baseAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); - } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - result = (iDynTree::SpatialAcc *) &((iDynTree::FreeFloatingAcc const *)arg1)->baseAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); + (void)argv; + result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57432,51 +60840,26 @@ int _wrap_FreeFloatingAcc_baseAcc__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_FreeFloatingAcc_baseAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_FreeFloatingAcc_baseAcc__SWIG_0(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_FreeFloatingAcc_baseAcc__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingAcc_baseAcc'." - " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingAcc::baseAcc()\n" - " iDynTree::FreeFloatingAcc::baseAcc() const\n"); - return 1; -} - - -int _wrap_FreeFloatingAcc_jointAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; - void *argp1 = 0 ; +int _wrap_new_DOFSpatialMotionArray__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + iDynTree::DOFSpatialMotionArray *result = 0 ; - if (!SWIG_check_num_args("FreeFloatingAcc_jointAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("new_DOFSpatialMotionArray",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_jointAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingAcc const *)arg1)->jointAcc(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::DOFSpatialMotionArray *)new iDynTree::DOFSpatialMotionArray((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57484,51 +60867,63 @@ int _wrap_FreeFloatingAcc_jointAcc__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_FreeFloatingAcc_jointAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_DOFSpatialMotionArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_DOFSpatialMotionArray__SWIG_1(resc,resv,argc,argv); + } if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_FreeFloatingAcc_jointAcc__SWIG_0(resc,resv,argc,argv); + return _wrap_new_DOFSpatialMotionArray__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_FreeFloatingAcc_jointAcc__SWIG_1(resc,resv,argc,argv); + return _wrap_new_DOFSpatialMotionArray__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingAcc_jointAcc'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_DOFSpatialMotionArray'." " Possible C/C++ prototypes are:\n" - " iDynTree::FreeFloatingAcc::jointAcc()\n" - " iDynTree::FreeFloatingAcc::jointAcc() const\n"); + " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray(std::size_t)\n" + " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray()\n" + " iDynTree::DOFSpatialMotionArray::DOFSpatialMotionArray(iDynTree::Model const &)\n"); return 1; } -int _wrap_FreeFloatingAcc_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; +int _wrap_DOFSpatialMotionArray_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; + std::size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - unsigned int result; - if (!SWIG_check_num_args("FreeFloatingAcc_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialMotionArray_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - result = (unsigned int)((iDynTree::FreeFloatingAcc const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57536,25 +60931,32 @@ int _wrap_FreeFloatingAcc_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_delete_FreeFloatingAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; +int _wrap_DOFSpatialMotionArray_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_FreeFloatingAcc",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialMotionArray_resize",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_resize" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); } - arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialMotionArray_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -57563,71 +60965,73 @@ int _wrap_delete_FreeFloatingAcc(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_ContactWrench_contactPoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Position *result = 0 ; - - if (!SWIG_check_num_args("ContactWrench_contactPoint",argc,1,1,0)) { - SWIG_fail; +int _wrap_DOFSpatialMotionArray_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_DOFSpatialMotionArray_resize__SWIG_1(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactPoint" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialMotionArray_resize__SWIG_0(resc,resv,argc,argv); + } + } } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); - result = (iDynTree::Position *) &(arg1)->contactPoint(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialMotionArray_resize'." + " Possible C/C++ prototypes are:\n" + " iDynTree::DOFSpatialMotionArray::resize(std::size_t const)\n" + " iDynTree::DOFSpatialMotionArray::resize(iDynTree::Model const &)\n"); return 1; } -int _wrap_ContactWrench_contactWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; +int _wrap_DOFSpatialMotionArray_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + bool result; - if (!SWIG_check_num_args("ContactWrench_contactWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialMotionArray_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); - result = (iDynTree::Wrench *) &(arg1)->contactWrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_ContactWrench_contactId(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::size_t *result = 0 ; - - if (!SWIG_check_num_args("ContactWrench_contactId",argc,1,1,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactId" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DOFSpatialMotionArray_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); - result = (std::size_t *) &(arg1)->contactId(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__size_t, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::DOFSpatialMotionArray const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57635,23 +61039,31 @@ int _wrap_ContactWrench_contactId(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_ContactWrench_contactPoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; +int _wrap_DOFSpatialMotionArray_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Position *result = 0 ; + iDynTree::SpatialMotionVector *result = 0 ; - if (!SWIG_check_num_args("ContactWrench_contactPoint",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialMotionArray_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactPoint" "', argument " "1"" of type '" "iDynTree::ContactWrench const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); - result = (iDynTree::Position *) &((iDynTree::ContactWrench const *)arg1)->contactPoint(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::SpatialMotionVector *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57659,51 +61071,31 @@ int _wrap_ContactWrench_contactPoint__SWIG_1(int resc, mxArray *resv[], int argc } -int _wrap_ContactWrench_contactPoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ContactWrench_contactPoint__SWIG_0(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ContactWrench_contactPoint__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ContactWrench_contactPoint'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ContactWrench::contactPoint()\n" - " iDynTree::ContactWrench::contactPoint() const\n"); - return 1; -} - - -int _wrap_ContactWrench_contactWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; +int _wrap_DOFSpatialMotionArray_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Wrench *result = 0 ; + iDynTree::SpatialMotionVector *result = 0 ; - if (!SWIG_check_num_args("ContactWrench_contactWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("DOFSpatialMotionArray_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DOFSpatialMotionArray_paren" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray const *""'"); } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); - result = (iDynTree::Wrench *) &((iDynTree::ContactWrench const *)arg1)->contactWrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DOFSpatialMotionArray_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::SpatialMotionVector *) &((iDynTree::DOFSpatialMotionArray const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialMotionVector, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57711,67 +61103,62 @@ int _wrap_ContactWrench_contactWrench__SWIG_1(int resc, mxArray *resv[], int arg } -int _wrap_ContactWrench_contactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 1) { +int _wrap_DOFSpatialMotionArray_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ContactWrench_contactWrench__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialMotionArray_paren__SWIG_0(resc,resv,argc,argv); + } } } - if (argc == 1) { + if (argc == 2) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ContactWrench_contactWrench__SWIG_1(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DOFSpatialMotionArray_paren__SWIG_1(resc,resv,argc,argv); + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ContactWrench_contactWrench'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DOFSpatialMotionArray_paren'." " Possible C/C++ prototypes are:\n" - " iDynTree::ContactWrench::contactWrench()\n" - " iDynTree::ContactWrench::contactWrench() const\n"); - return 1; -} - - -int _wrap_new_ContactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::ContactWrench *result = 0 ; - - if (!SWIG_check_num_args("new_ContactWrench",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::ContactWrench *)new iDynTree::ContactWrench(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::DOFSpatialMotionArray::operator ()(size_t const)\n" + " iDynTree::DOFSpatialMotionArray::operator ()(size_t const) const\n"); return 1; } -int _wrap_delete_ContactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; +int _wrap_delete_DOFSpatialMotionArray(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DOFSpatialMotionArray *arg1 = (iDynTree::DOFSpatialMotionArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_ContactWrench",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_DOFSpatialMotionArray",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ContactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DOFSpatialMotionArray" "', argument " "1"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); } - arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + arg1 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp1); if (is_owned) { delete arg1; } @@ -57783,23 +61170,23 @@ int _wrap_delete_ContactWrench(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_new_LinkContactWrenches__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::size_t arg1 ; +int _wrap_new_FrameFreeFloatingJacobian__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + size_t arg1 ; size_t val1 ; int ecode1 = 0 ; mxArray * _out; - iDynTree::LinkContactWrenches *result = 0 ; + iDynTree::FrameFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("new_LinkContactWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } ecode1 = SWIG_AsVal_size_t(argv[0], &val1); if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "std::size_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "size_t""'"); } - arg1 = static_cast< std::size_t >(val1); - result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); + arg1 = static_cast< size_t >(val1); + result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57807,16 +61194,16 @@ int _wrap_new_LinkContactWrenches__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_new_LinkContactWrenches__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FrameFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::LinkContactWrenches *result = 0 ; + iDynTree::FrameFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("new_LinkContactWrenches",argc,0,0,0)) { + if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); + result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57824,26 +61211,26 @@ int _wrap_new_LinkContactWrenches__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_LinkContactWrenches__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FrameFreeFloatingJacobian__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkContactWrenches *result = 0 ; + iDynTree::FrameFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("new_LinkContactWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("new_FrameFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); + result = (iDynTree::FrameFreeFloatingJacobian *)new iDynTree::FrameFreeFloatingJacobian((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -57851,9 +61238,9 @@ int _wrap_new_LinkContactWrenches__SWIG_2(int resc, mxArray *resv[], int argc, m } -int _wrap_new_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FrameFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 0) { - return _wrap_new_LinkContactWrenches__SWIG_1(resc,resv,argc,argv); + return _wrap_new_FrameFreeFloatingJacobian__SWIG_1(resc,resv,argc,argv); } if (argc == 1) { int _v; @@ -57861,7 +61248,7 @@ int _wrap_new_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray * int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_LinkContactWrenches__SWIG_2(resc,resv,argc,argv); + return _wrap_new_FrameFreeFloatingJacobian__SWIG_2(resc,resv,argc,argv); } } if (argc == 1) { @@ -57871,52 +61258,21 @@ int _wrap_new_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray * _v = SWIG_CheckState(res); } if (_v) { - return _wrap_new_LinkContactWrenches__SWIG_0(resc,resv,argc,argv); + return _wrap_new_FrameFreeFloatingJacobian__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkContactWrenches'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FrameFreeFloatingJacobian'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkContactWrenches::LinkContactWrenches(std::size_t)\n" - " iDynTree::LinkContactWrenches::LinkContactWrenches()\n" - " iDynTree::LinkContactWrenches::LinkContactWrenches(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_LinkContactWrenches_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - std::size_t arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - - if (!SWIG_check_num_args("LinkContactWrenches_resize",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "std::size_t""'"); - } - arg2 = static_cast< std::size_t >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian(size_t)\n" + " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian()\n" + " iDynTree::FrameFreeFloatingJacobian::FrameFreeFloatingJacobian(iDynTree::Model const &)\n"); return 1; } -int _wrap_LinkContactWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; +int _wrap_FrameFreeFloatingJacobian_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -57924,95 +61280,59 @@ int _wrap_LinkContactWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("LinkContactWrenches_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("FrameFreeFloatingJacobian_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_LinkContactWrenches_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinkContactWrenches_resize__SWIG_1(resc,resv,argc,argv); - } - } - } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkContactWrenches_resize__SWIG_0(resc,resv,argc,argv); - } - } + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FrameFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkContactWrenches_resize'." - " Possible C/C++ prototypes are:\n" - " iDynTree::LinkContactWrenches::resize(std::size_t)\n" - " iDynTree::LinkContactWrenches::resize(iDynTree::Model const &)\n"); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinkContactWrenches_getNrOfContactsForLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; +int _wrap_FrameFreeFloatingJacobian_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - size_t result; + bool result; - if (!SWIG_check_num_args("LinkContactWrenches_getNrOfContactsForLink",argc,2,2,0)) { + if (!SWIG_check_num_args("FrameFreeFloatingJacobian_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_getNrOfContactsForLink" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_getNrOfContactsForLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = ((iDynTree::LinkContactWrenches const *)arg1)->getNrOfContactsForLink(arg2); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FrameFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::FrameFreeFloatingJacobian const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58020,37 +61340,25 @@ int _wrap_LinkContactWrenches_getNrOfContactsForLink(int resc, mxArray *resv[], } -int _wrap_LinkContactWrenches_setNrOfContactsForLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; - size_t arg3 ; +int _wrap_delete_FrameFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FrameFreeFloatingJacobian *arg1 = (iDynTree::FrameFreeFloatingJacobian *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("LinkContactWrenches_setNrOfContactsForLink",argc,3,3,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_FrameFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FrameFreeFloatingJacobian, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FrameFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::FrameFreeFloatingJacobian *""'"); + } + arg1 = reinterpret_cast< iDynTree::FrameFreeFloatingJacobian * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "3"" of type '" "size_t""'"); - } - arg3 = static_cast< size_t >(val3); - (arg1)->setNrOfContactsForLink(arg2,arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -58059,23 +61367,23 @@ int _wrap_LinkContactWrenches_setNrOfContactsForLink(int resc, mxArray *resv[], } -int _wrap_LinkContactWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_MomentumFreeFloatingJacobian__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - size_t result; + iDynTree::MomentumFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("LinkContactWrenches_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - result = ((iDynTree::LinkContactWrenches const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "size_t""'"); + } + arg1 = static_cast< size_t >(val1); + result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58083,39 +61391,16 @@ int _wrap_LinkContactWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, } -int _wrap_LinkContactWrenches_contactWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; - size_t arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; +int _wrap_new_MomentumFreeFloatingJacobian__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::ContactWrench *result = 0 ; + iDynTree::MomentumFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("LinkContactWrenches_contactWrench",argc,3,3,0)) { + if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_contactWrench" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); - } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_contactWrench" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_contactWrench" "', argument " "3"" of type '" "size_t""'"); - } - arg3 = static_cast< size_t >(val3); - result = (iDynTree::ContactWrench *) &(arg1)->contactWrench(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); + (void)argv; + result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58123,39 +61408,26 @@ int _wrap_LinkContactWrenches_contactWrench__SWIG_0(int resc, mxArray *resv[], i } -int _wrap_LinkContactWrenches_contactWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - iDynTree::LinkIndex arg2 ; - size_t arg3 ; - void *argp1 = 0 ; +int _wrap_new_MomentumFreeFloatingJacobian__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::ContactWrench *result = 0 ; + iDynTree::MomentumFreeFloatingJacobian *result = 0 ; - if (!SWIG_check_num_args("LinkContactWrenches_contactWrench",argc,3,3,0)) { + if (!SWIG_check_num_args("new_MomentumFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_contactWrench" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_contactWrench" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_contactWrench" "', argument " "3"" of type '" "size_t""'"); - } - arg3 = static_cast< size_t >(val3); - result = (iDynTree::ContactWrench *) &((iDynTree::LinkContactWrenches const *)arg1)->contactWrench(arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::MomentumFreeFloatingJacobian *)new iDynTree::MomentumFreeFloatingJacobian((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58163,86 +61435,66 @@ int _wrap_LinkContactWrenches_contactWrench__SWIG_1(int resc, mxArray *resv[], i } -int _wrap_LinkContactWrenches_contactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_new_MomentumFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_MomentumFreeFloatingJacobian__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkContactWrenches_contactWrench__SWIG_0(resc,resv,argc,argv); - } - } + return _wrap_new_MomentumFreeFloatingJacobian__SWIG_2(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinkContactWrenches_contactWrench__SWIG_1(resc,resv,argc,argv); - } - } + return _wrap_new_MomentumFreeFloatingJacobian__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkContactWrenches_contactWrench'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_MomentumFreeFloatingJacobian'." " Possible C/C++ prototypes are:\n" - " iDynTree::LinkContactWrenches::contactWrench(iDynTree::LinkIndex const,size_t const)\n" - " iDynTree::LinkContactWrenches::contactWrench(iDynTree::LinkIndex const,size_t const) const\n"); + " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian(size_t)\n" + " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian()\n" + " iDynTree::MomentumFreeFloatingJacobian::MomentumFreeFloatingJacobian(iDynTree::Model const &)\n"); return 1; } -int _wrap_LinkContactWrenches_computeNetWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; - iDynTree::LinkNetExternalWrenches *arg2 = 0 ; +int _wrap_MomentumFreeFloatingJacobian_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("LinkContactWrenches_computeNetWrenches",argc,2,2,0)) { + if (!SWIG_check_num_args("MomentumFreeFloatingJacobian_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "2"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "2"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MomentumFreeFloatingJacobian_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg2 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp2); - result = (bool)((iDynTree::LinkContactWrenches const *)arg1)->computeNetWrenches(*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58250,34 +61502,34 @@ int _wrap_LinkContactWrenches_computeNetWrenches(int resc, mxArray *resv[], int } -int _wrap_LinkContactWrenches_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; +int _wrap_MomentumFreeFloatingJacobian_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("LinkContactWrenches_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("MomentumFreeFloatingJacobian_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_toString" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian const *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "MomentumFreeFloatingJacobian_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::LinkContactWrenches const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + result = (bool)((iDynTree::MomentumFreeFloatingJacobian const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58285,22 +61537,22 @@ int _wrap_LinkContactWrenches_toString(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_delete_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; +int _wrap_delete_MomentumFreeFloatingJacobian(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::MomentumFreeFloatingJacobian *arg1 = (iDynTree::MomentumFreeFloatingJacobian *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_LinkContactWrenches",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_MomentumFreeFloatingJacobian",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__MomentumFreeFloatingJacobian, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_MomentumFreeFloatingJacobian" "', argument " "1"" of type '" "iDynTree::MomentumFreeFloatingJacobian *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + arg1 = reinterpret_cast< iDynTree::MomentumFreeFloatingJacobian * >(argp1); if (is_owned) { delete arg1; } @@ -58312,16 +61564,23 @@ int _wrap_delete_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_getRandomLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FreeFloatingMassMatrix__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - iDynTree::Link result; + iDynTree::FreeFloatingMassMatrix *result = 0 ; - if (!SWIG_check_num_args("getRandomLink",argc,0,0,0)) { + if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = iDynTree::getRandomLink(); - _out = SWIG_NewPointerObj((new iDynTree::Link(static_cast< const iDynTree::Link& >(result))), SWIGTYPE_p_iDynTree__Link, SWIG_POINTER_OWN | 0 ); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "size_t""'"); + } + arg1 = static_cast< size_t >(val1); + result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58329,53 +61588,16 @@ int _wrap_getRandomLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_addRandomLinkToModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::string arg2 ; - std::string arg3 ; - bool arg4 ; - void *argp1 = 0 ; - int res1 = 0 ; - bool val4 ; - int ecode4 = 0 ; +int _wrap_new_FreeFloatingMassMatrix__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::FreeFloatingMassMatrix *result = 0 ; - if (!SWIG_check_num_args("addRandomLinkToModel",argc,4,4,0)) { + if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "2"" of type '" "std::string""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "3"" of type '" "std::string""'"); - } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - ecode4 = SWIG_AsVal_bool(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "addRandomLinkToModel" "', argument " "4"" of type '" "bool""'"); - } - arg4 = static_cast< bool >(val4); - iDynTree::addRandomLinkToModel(*arg1,arg2,arg3,arg4); - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58383,45 +61605,26 @@ int _wrap_addRandomLinkToModel__SWIG_0(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_addRandomLinkToModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FreeFloatingMassMatrix__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; - std::string arg2 ; - std::string arg3 ; - void *argp1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; + iDynTree::FreeFloatingMassMatrix *result = 0 ; - if (!SWIG_check_num_args("addRandomLinkToModel",argc,3,3,0)) { + if (!SWIG_check_num_args("new_FreeFloatingMassMatrix",argc,1,1,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "2"" of type '" "std::string""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "3"" of type '" "std::string""'"); - } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - iDynTree::addRandomLinkToModel(*arg1,arg2,arg3); - _out = (mxArray*)0; + result = (iDynTree::FreeFloatingMassMatrix *)new iDynTree::FreeFloatingMassMatrix((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58429,94 +61632,92 @@ int _wrap_addRandomLinkToModel__SWIG_1(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_addRandomLinkToModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_new_FreeFloatingMassMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FreeFloatingMassMatrix__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { int _v; void *vptr = 0; int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_addRandomLinkToModel__SWIG_1(resc,resv,argc,argv); - } - } + return _wrap_new_FreeFloatingMassMatrix__SWIG_2(resc,resv,argc,argv); } } - if (argc == 4) { + if (argc == 1) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_bool(argv[3], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_addRandomLinkToModel__SWIG_0(resc,resv,argc,argv); - } - } - } + } + if (_v) { + return _wrap_new_FreeFloatingMassMatrix__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'addRandomLinkToModel'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingMassMatrix'." " Possible C/C++ prototypes are:\n" - " iDynTree::addRandomLinkToModel(iDynTree::Model &,std::string,std::string,bool)\n" - " iDynTree::addRandomLinkToModel(iDynTree::Model &,std::string,std::string)\n"); + " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix(size_t)\n" + " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix()\n" + " iDynTree::FreeFloatingMassMatrix::FreeFloatingMassMatrix(iDynTree::Model const &)\n"); return 1; } -int _wrap_addRandomAdditionalFrameToModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::string arg2 ; - std::string arg3 ; +int _wrap_FreeFloatingMassMatrix_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingMassMatrix *arg1 = (iDynTree::FreeFloatingMassMatrix *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("addRandomAdditionalFrameToModel",argc,3,3,0)) { + if (!SWIG_check_num_args("FreeFloatingMassMatrix_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomAdditionalFrameToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingMassMatrix_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingMassMatrix *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomAdditionalFrameToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + arg1 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingMassMatrix_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomAdditionalFrameToModel" "', argument " "2"" of type '" "std::string""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingMassMatrix_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomAdditionalFrameToModel" "', argument " "3"" of type '" "std::string""'"); - } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_FreeFloatingMassMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingMassMatrix *arg1 = (iDynTree::FreeFloatingMassMatrix *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_FreeFloatingMassMatrix",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingMassMatrix" "', argument " "1"" of type '" "iDynTree::FreeFloatingMassMatrix *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp1); + if (is_owned) { + delete arg1; } - iDynTree::addRandomAdditionalFrameToModel(*arg1,arg2,arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -58525,26 +61726,43 @@ int _wrap_addRandomAdditionalFrameToModel(int resc, mxArray *resv[], int argc, m } -int _wrap_getRandomLinkIndexOfModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FreeFloatingPos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::FreeFloatingPos *result = 0 ; + + if (!SWIG_check_num_args("new_FreeFloatingPos",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::FreeFloatingPos *)new iDynTree::FreeFloatingPos(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingPos, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FreeFloatingPos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::FreeFloatingPos *result = 0 ; - if (!SWIG_check_num_args("getRandomLinkIndexOfModel",argc,1,1,0)) { + if (!SWIG_check_num_args("new_FreeFloatingPos",argc,1,1,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomLinkIndexOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomLinkIndexOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = iDynTree::getRandomLinkIndexOfModel((iDynTree::Model const &)*arg1); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + result = (iDynTree::FreeFloatingPos *)new iDynTree::FreeFloatingPos((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingPos, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58552,26 +61770,55 @@ int _wrap_getRandomLinkIndexOfModel(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_getRandomLinkOfModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_new_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FreeFloatingPos__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FreeFloatingPos__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingPos'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingPos::FreeFloatingPos()\n" + " iDynTree::FreeFloatingPos::FreeFloatingPos(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_FreeFloatingPos_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("getRandomLinkOfModel",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomLinkOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomLinkOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingPos_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = iDynTree::getRandomLinkOfModel((iDynTree::Model const &)*arg1); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingPos_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58579,23 +61826,23 @@ int _wrap_getRandomLinkOfModel(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_int2string(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - int arg1 ; - int val1 ; - int ecode1 = 0 ; +int _wrap_FreeFloatingPos_worldBasePos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - std::string result; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("int2string",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_worldBasePos",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "int2string" "', argument " "1"" of type '" "int""'"); - } - arg1 = static_cast< int >(val1); - result = iDynTree::int2string(arg1); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_worldBasePos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + result = (iDynTree::Transform *) &(arg1)->worldBasePos(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58603,31 +61850,23 @@ int _wrap_int2string(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_getRandomModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - unsigned int arg1 ; - size_t arg2 ; - unsigned int val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_FreeFloatingPos_jointPos__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Model result; + iDynTree::JointPosDoubleArray *result = 0 ; - if (!SWIG_check_num_args("getRandomModel",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_jointPos",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomModel" "', argument " "1"" of type '" "unsigned int""'"); - } - arg1 = static_cast< unsigned int >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomModel" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = iDynTree::getRandomModel(arg1,arg2); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_jointPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + result = (iDynTree::JointPosDoubleArray *) &(arg1)->jointPos(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58635,23 +61874,23 @@ int _wrap_getRandomModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_getRandomModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - unsigned int arg1 ; - unsigned int val1 ; - int ecode1 = 0 ; +int _wrap_FreeFloatingPos_worldBasePos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Model result; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("getRandomModel",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_worldBasePos",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomModel" "', argument " "1"" of type '" "unsigned int""'"); - } - arg1 = static_cast< unsigned int >(val1); - result = iDynTree::getRandomModel(arg1); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_worldBasePos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + result = (iDynTree::Transform *) &((iDynTree::FreeFloatingPos const *)arg1)->worldBasePos(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58659,131 +61898,51 @@ int _wrap_getRandomModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_getRandomModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_FreeFloatingPos_worldBasePos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; - { - int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); if (_v) { - return _wrap_getRandomModel__SWIG_1(resc,resv,argc,argv); + return _wrap_FreeFloatingPos_worldBasePos__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; - { - int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_getRandomModel__SWIG_0(resc,resv,argc,argv); - } + return _wrap_FreeFloatingPos_worldBasePos__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'getRandomModel'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingPos_worldBasePos'." " Possible C/C++ prototypes are:\n" - " iDynTree::getRandomModel(unsigned int,size_t)\n" - " iDynTree::getRandomModel(unsigned int)\n"); - return 1; -} - - -int _wrap_getRandomChain__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - unsigned int arg1 ; - size_t arg2 ; - bool arg3 ; - unsigned int val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - bool val3 ; - int ecode3 = 0 ; - mxArray * _out; - iDynTree::Model result; - - if (!SWIG_check_num_args("getRandomChain",argc,3,3,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); - } - arg1 = static_cast< unsigned int >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomChain" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - ecode3 = SWIG_AsVal_bool(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "getRandomChain" "', argument " "3"" of type '" "bool""'"); - } - arg3 = static_cast< bool >(val3); - result = iDynTree::getRandomChain(arg1,arg2,arg3); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + " iDynTree::FreeFloatingPos::worldBasePos()\n" + " iDynTree::FreeFloatingPos::worldBasePos() const\n"); return 1; } -int _wrap_getRandomChain__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - unsigned int arg1 ; - size_t arg2 ; - unsigned int val1 ; - int ecode1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_FreeFloatingPos_jointPos__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Model result; + iDynTree::JointPosDoubleArray *result = 0 ; - if (!SWIG_check_num_args("getRandomChain",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_jointPos",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); - } - arg1 = static_cast< unsigned int >(val1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomChain" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = iDynTree::getRandomChain(arg1,arg2); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_getRandomChain__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - unsigned int arg1 ; - unsigned int val1 ; - int ecode1 = 0 ; - mxArray * _out; - iDynTree::Model result; - - if (!SWIG_check_num_args("getRandomChain",argc,1,1,0)) { - SWIG_fail; + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_jointPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); } - ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); - } - arg1 = static_cast< unsigned int >(val1); - result = iDynTree::getRandomChain(arg1); - _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + result = (iDynTree::JointPosDoubleArray *) &((iDynTree::FreeFloatingPos const *)arg1)->jointPos(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58791,95 +61950,51 @@ int _wrap_getRandomChain__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_getRandomChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_FreeFloatingPos_jointPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 1) { int _v; - { - int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_getRandomChain__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 2) { - int _v; - { - int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_getRandomChain__SWIG_1(resc,resv,argc,argv); - } + return _wrap_FreeFloatingPos_jointPos__SWIG_0(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 1) { int _v; - { - int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_bool(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_getRandomChain__SWIG_0(resc,resv,argc,argv); - } - } + return _wrap_FreeFloatingPos_jointPos__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'getRandomChain'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingPos_jointPos'." " Possible C/C++ prototypes are:\n" - " iDynTree::getRandomChain(unsigned int,size_t,bool)\n" - " iDynTree::getRandomChain(unsigned int,size_t)\n" - " iDynTree::getRandomChain(unsigned int)\n"); + " iDynTree::FreeFloatingPos::jointPos()\n" + " iDynTree::FreeFloatingPos::jointPos() const\n"); return 1; } -int _wrap_getRandomJointPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::VectorDynSize *arg1 = 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_FreeFloatingPos_getNrOfPosCoords(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; + unsigned int result; - if (!SWIG_check_num_args("getRandomJointPositions",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingPos_getNrOfPosCoords",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomJointPositions" "', argument " "1"" of type '" "iDynTree::VectorDynSize &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomJointPositions" "', argument " "1"" of type '" "iDynTree::VectorDynSize &""'"); - } - arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "getRandomJointPositions" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomJointPositions" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingPos_getNrOfPosCoords" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos const *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - iDynTree::getRandomJointPositions(*arg1,(iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + result = (unsigned int)((iDynTree::FreeFloatingPos const *)arg1)->getNrOfPosCoords(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58887,59 +62002,70 @@ int _wrap_getRandomJointPositions(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_getRandomInverseDynamicsInputs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::FreeFloatingPos *arg1 = 0 ; - iDynTree::FreeFloatingVel *arg2 = 0 ; - iDynTree::FreeFloatingAcc *arg3 = 0 ; - iDynTree::LinkNetExternalWrenches *arg4 = 0 ; +int _wrap_delete_FreeFloatingPos(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = (iDynTree::FreeFloatingPos *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("getRandomInverseDynamicsInputs",argc,4,4,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_FreeFloatingPos",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingPos, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomInverseDynamicsInputs" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingPos" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos *""'"); } arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "getRandomInverseDynamicsInputs" "', argument " "2"" of type '" "iDynTree::FreeFloatingVel &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "2"" of type '" "iDynTree::FreeFloatingVel &""'"); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "getRandomInverseDynamicsInputs" "', argument " "3"" of type '" "iDynTree::FreeFloatingAcc &""'"); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::FreeFloatingGeneralizedTorques *result = 0 ; + + if (!SWIG_check_num_args("new_FreeFloatingGeneralizedTorques",argc,0,0,0)) { + SWIG_fail; } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "3"" of type '" "iDynTree::FreeFloatingAcc &""'"); + (void)argv; + result = (iDynTree::FreeFloatingGeneralizedTorques *)new iDynTree::FreeFloatingGeneralizedTorques(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FreeFloatingGeneralizedTorques__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::FreeFloatingGeneralizedTorques *result = 0 ; + + if (!SWIG_check_num_args("new_FreeFloatingGeneralizedTorques",argc,1,1,0)) { + SWIG_fail; } - arg3 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "getRandomInverseDynamicsInputs" "', argument " "4"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "4"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg4 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp4); - result = (bool)iDynTree::getRandomInverseDynamicsInputs(*arg1,*arg2,*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::FreeFloatingGeneralizedTorques *)new iDynTree::FreeFloatingGeneralizedTorques((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58947,37 +62073,55 @@ int _wrap_getRandomInverseDynamicsInputs(int resc, mxArray *resv[], int argc, mx } -int _wrap_removeFakeLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; +int _wrap_new_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FreeFloatingGeneralizedTorques__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FreeFloatingGeneralizedTorques__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingGeneralizedTorques'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingGeneralizedTorques::FreeFloatingGeneralizedTorques()\n" + " iDynTree::FreeFloatingGeneralizedTorques::FreeFloatingGeneralizedTorques(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_FreeFloatingGeneralizedTorques_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; iDynTree::Model *arg2 = 0 ; - void *argp1 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("removeFakeLinks",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "removeFakeLinks" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "removeFakeLinks" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "removeFakeLinks" "', argument " "2"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "removeFakeLinks" "', argument " "2"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingGeneralizedTorques_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)iDynTree::removeFakeLinks((iDynTree::Model const &)*arg1,*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -58985,154 +62129,123 @@ int _wrap_removeFakeLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_createReducedModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::vector< std::string,std::allocator< std::string > > *arg2 = 0 ; - iDynTree::Model *arg3 = 0 ; - void *argp1 ; +int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - bool result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("createReducedModel",argc,3,3,0)) { + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_baseWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "createReducedModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; - res2 = swig::asptr(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "createReducedModel" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - arg2 = ptr; - } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "createReducedModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_baseWrench" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); } - arg3 = reinterpret_cast< iDynTree::Model * >(argp3); - result = (bool)iDynTree::createReducedModel((iDynTree::Model const &)*arg1,(std::vector< std::string,std::allocator< std::string > > const &)*arg2,*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + result = (iDynTree::Wrench *) &(arg1)->baseWrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_createModelWithNormalizedJointNumbering(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::string *arg2 = 0 ; - iDynTree::Model *arg3 = 0 ; - void *argp1 ; +int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - bool result; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("createModelWithNormalizedJointNumbering",argc,3,3,0)) { + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_jointTorques",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "3"" of type '" "iDynTree::Model &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "3"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_jointTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); } - arg3 = reinterpret_cast< iDynTree::Model * >(argp3); - result = (bool)iDynTree::createModelWithNormalizedJointNumbering((iDynTree::Model const &)*arg1,(std::string const &)*arg2,*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointTorques(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_extractSubModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::Model *arg3 = 0 ; - void *argp1 ; +int _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - bool result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("extractSubModel",argc,3,3,0)) { + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_baseWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "extractSubModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_baseWrench" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "extractSubModel" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + result = (iDynTree::Wrench *) &((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->baseWrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_FreeFloatingGeneralizedTorques_baseWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_0(resc,resv,argc,argv); + } } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingGeneralizedTorques_baseWrench__SWIG_1(resc,resv,argc,argv); + } } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "extractSubModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingGeneralizedTorques_baseWrench'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingGeneralizedTorques::baseWrench()\n" + " iDynTree::FreeFloatingGeneralizedTorques::baseWrench() const\n"); + return 1; +} + + +int _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointDOFsDoubleArray *result = 0 ; + + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_jointTorques",argc,1,1,0)) { + SWIG_fail; } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_jointTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); } - arg3 = reinterpret_cast< iDynTree::Model * >(argp3); - result = (bool)iDynTree::extractSubModel((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->jointTorques(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59140,16 +62253,51 @@ int _wrap_extractSubModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_new_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_FreeFloatingGeneralizedTorques_jointTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_0(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingGeneralizedTorques_jointTorques__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingGeneralizedTorques_jointTorques'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingGeneralizedTorques::jointTorques()\n" + " iDynTree::FreeFloatingGeneralizedTorques::jointTorques() const\n"); + return 1; +} + + +int _wrap_FreeFloatingGeneralizedTorques_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SubModelDecomposition *result = 0 ; + unsigned int result; - if (!SWIG_check_num_args("new_SubModelDecomposition",argc,0,0,0)) { + if (!SWIG_check_num_args("FreeFloatingGeneralizedTorques_getNrOfDOFs",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SubModelDecomposition *)new iDynTree::SubModelDecomposition(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SubModelDecomposition, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingGeneralizedTorques_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); + result = (unsigned int)((iDynTree::FreeFloatingGeneralizedTorques const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59157,22 +62305,22 @@ int _wrap_new_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_delete_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; +int _wrap_delete_FreeFloatingGeneralizedTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingGeneralizedTorques *arg1 = (iDynTree::FreeFloatingGeneralizedTorques *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; int is_owned; - if (!SWIG_check_num_args("delete_SubModelDecomposition",argc,1,1,0)) { + if (!SWIG_check_num_args("delete_FreeFloatingGeneralizedTorques",argc,1,1,0)) { SWIG_fail; } is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SubModelDecomposition" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingGeneralizedTorques" "', argument " "1"" of type '" "iDynTree::FreeFloatingGeneralizedTorques *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + arg1 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp1); if (is_owned) { delete arg1; } @@ -59184,90 +62332,98 @@ int _wrap_delete_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SubModelDecomposition_splitModelAlongJoints(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - iDynTree::Model *arg2 = 0 ; - iDynTree::Traversal *arg3 = 0 ; - std::vector< std::string,std::allocator< std::string > > *arg4 = 0 ; - void *argp1 = 0 ; +int _wrap_new_FreeFloatingVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::FreeFloatingVel *result = 0 ; + + if (!SWIG_check_num_args("new_FreeFloatingVel",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::FreeFloatingVel *)new iDynTree::FreeFloatingVel(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingVel, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_FreeFloatingVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - int res4 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + iDynTree::FreeFloatingVel *result = 0 ; - if (!SWIG_check_num_args("SubModelDecomposition_splitModelAlongJoints",argc,4,4,0)) { + if (!SWIG_check_num_args("new_FreeFloatingVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); - } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); - { - std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; - res4 = swig::asptr(argv[3], &ptr); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - arg4 = ptr; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - result = (bool)(arg1)->splitModelAlongJoints((iDynTree::Model const &)*arg2,(iDynTree::Traversal const &)*arg3,(std::vector< std::string,std::allocator< std::string > > const &)*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::FreeFloatingVel *)new iDynTree::FreeFloatingVel((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingVel, 1 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: - if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_SubModelDecomposition_setNrOfSubModels(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - size_t arg2 ; +int _wrap_new_FreeFloatingVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FreeFloatingVel__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FreeFloatingVel__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingVel'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingVel::FreeFloatingVel()\n" + " iDynTree::FreeFloatingVel::FreeFloatingVel(iDynTree::Model const &)\n"); + return 1; +} + + +int _wrap_FreeFloatingVel_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SubModelDecomposition_setNrOfSubModels",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_setNrOfSubModels" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_setNrOfSubModels" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - (arg1)->setNrOfSubModels(arg2); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingVel_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingVel_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -59276,23 +62432,23 @@ int _wrap_SubModelDecomposition_setNrOfSubModels(int resc, mxArray *resv[], int } -int _wrap_SubModelDecomposition_getNrOfSubModels(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; +int _wrap_FreeFloatingVel_baseVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("SubModelDecomposition_getNrOfSubModels",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_baseVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getNrOfSubModels" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_baseVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - result = ((iDynTree::SubModelDecomposition const *)arg1)->getNrOfSubModels(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + result = (iDynTree::Twist *) &(arg1)->baseVel(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59300,23 +62456,23 @@ int _wrap_SubModelDecomposition_getNrOfSubModels(int resc, mxArray *resv[], int } -int _wrap_SubModelDecomposition_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; +int _wrap_FreeFloatingVel_jointVel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("SubModelDecomposition_getNrOfLinks",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_jointVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_jointVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - result = ((iDynTree::SubModelDecomposition const *)arg1)->getNrOfLinks(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointVel(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59324,31 +62480,23 @@ int _wrap_SubModelDecomposition_getNrOfLinks(int resc, mxArray *resv[], int argc } -int _wrap_SubModelDecomposition_getTraversal__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - size_t arg2 ; +int _wrap_FreeFloatingVel_baseVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::Traversal *result = 0 ; + iDynTree::Twist *result = 0 ; - if (!SWIG_check_num_args("SubModelDecomposition_getTraversal",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_baseVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getTraversal" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_baseVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getTraversal" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::Traversal *) &(arg1)->getTraversal(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Traversal, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + result = (iDynTree::Twist *) &((iDynTree::FreeFloatingVel const *)arg1)->baseVel(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Twist, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59356,31 +62504,51 @@ int _wrap_SubModelDecomposition_getTraversal__SWIG_0(int resc, mxArray *resv[], } -int _wrap_SubModelDecomposition_getTraversal__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - size_t arg2 ; +int _wrap_FreeFloatingVel_baseVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingVel_baseVel__SWIG_0(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingVel_baseVel__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingVel_baseVel'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingVel::baseVel()\n" + " iDynTree::FreeFloatingVel::baseVel() const\n"); + return 1; +} + + +int _wrap_FreeFloatingVel_jointVel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::Traversal *result = 0 ; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("SubModelDecomposition_getTraversal",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_jointVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getTraversal" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_jointVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getTraversal" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::Traversal *) &((iDynTree::SubModelDecomposition const *)arg1)->getTraversal(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Traversal, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingVel const *)arg1)->jointVel(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59388,73 +62556,51 @@ int _wrap_SubModelDecomposition_getTraversal__SWIG_1(int resc, mxArray *resv[], } -int _wrap_SubModelDecomposition_getTraversal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_FreeFloatingVel_jointVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SubModelDecomposition_getTraversal__SWIG_0(resc,resv,argc,argv); - } + return _wrap_FreeFloatingVel_jointVel__SWIG_0(resc,resv,argc,argv); } } - if (argc == 2) { + if (argc == 1) { int _v; void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0); + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SubModelDecomposition_getTraversal__SWIG_1(resc,resv,argc,argv); - } + return _wrap_FreeFloatingVel_jointVel__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SubModelDecomposition_getTraversal'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingVel_jointVel'." " Possible C/C++ prototypes are:\n" - " iDynTree::SubModelDecomposition::getTraversal(size_t const)\n" - " iDynTree::SubModelDecomposition::getTraversal(size_t const) const\n"); + " iDynTree::FreeFloatingVel::jointVel()\n" + " iDynTree::FreeFloatingVel::jointVel() const\n"); return 1; } -int _wrap_SubModelDecomposition_getSubModelOfLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_FreeFloatingVel_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::LinkIndex temp2 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - size_t result; + unsigned int result; - if (!SWIG_check_num_args("SubModelDecomposition_getSubModelOfLink",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingVel_getNrOfDOFs",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getSubModelOfLink" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingVel_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel const *""'"); } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getSubModelOfLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = ((iDynTree::SubModelDecomposition const *)arg1)->getSubModelOfLink((iDynTree::LinkIndex const &)*arg2); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + result = (unsigned int)((iDynTree::FreeFloatingVel const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59462,44 +62608,26 @@ int _wrap_SubModelDecomposition_getSubModelOfLink(int resc, mxArray *resv[], int } -int _wrap_SubModelDecomposition_getSubModelOfFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; - iDynTree::Model *arg2 = 0 ; - iDynTree::FrameIndex *arg3 = 0 ; +int _wrap_delete_FreeFloatingVel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingVel *arg1 = (iDynTree::FreeFloatingVel *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - iDynTree::FrameIndex temp3 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; - size_t result; - if (!SWIG_check_num_args("SubModelDecomposition_getSubModelOfFrame",argc,3,3,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_FreeFloatingVel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingVel, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingVel" "', argument " "1"" of type '" "iDynTree::FreeFloatingVel *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "3"" of type '" "iDynTree::FrameIndex""'"); - } - temp3 = static_cast< iDynTree::FrameIndex >(val3); - arg3 = &temp3; - result = ((iDynTree::SubModelDecomposition const *)arg1)->getSubModelOfFrame((iDynTree::Model const &)*arg2,(iDynTree::FrameIndex const &)*arg3); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59507,58 +62635,16 @@ int _wrap_SubModelDecomposition_getSubModelOfFrame(int resc, mxArray *resv[], in } -int _wrap_computeTransformToTraversalBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::JointPosDoubleArray *arg3 = 0 ; - iDynTree::LinkPositions *arg4 = 0 ; - void *argp1 ; - int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; +int _wrap_new_FreeFloatingAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::FreeFloatingAcc *result = 0 ; - if (!SWIG_check_num_args("computeTransformToTraversalBase",argc,4,4,0)) { + if (!SWIG_check_num_args("new_FreeFloatingAcc",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "computeTransformToTraversalBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "computeTransformToTraversalBase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "computeTransformToTraversalBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); - } - arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "computeTransformToTraversalBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); - iDynTree::computeTransformToTraversalBase((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4); - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::FreeFloatingAcc *)new iDynTree::FreeFloatingAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingAcc, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59566,58 +62652,26 @@ int _wrap_computeTransformToTraversalBase(int resc, mxArray *resv[], int argc, m } -int _wrap_computeTransformToSubModelBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_FreeFloatingAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; - iDynTree::SubModelDecomposition *arg2 = 0 ; - iDynTree::JointPosDoubleArray *arg3 = 0 ; - iDynTree::LinkPositions *arg4 = 0 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; + iDynTree::FreeFloatingAcc *result = 0 ; - if (!SWIG_check_num_args("computeTransformToSubModelBase",argc,4,4,0)) { + if (!SWIG_check_num_args("new_FreeFloatingAcc",argc,1,1,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "computeTransformToSubModelBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "computeTransformToSubModelBase" "', argument " "2"" of type '" "iDynTree::SubModelDecomposition const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "2"" of type '" "iDynTree::SubModelDecomposition const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "computeTransformToSubModelBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); - } - arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "computeTransformToSubModelBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); - iDynTree::computeTransformToSubModelBase((iDynTree::Model const &)*arg1,(iDynTree::SubModelDecomposition const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4); - _out = (mxArray*)0; + result = (iDynTree::FreeFloatingAcc *)new iDynTree::FreeFloatingAcc((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__FreeFloatingAcc, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59625,67 +62679,55 @@ int _wrap_computeTransformToSubModelBase(int resc, mxArray *resv[], int argc, mx } -int _wrap_SolidShapesVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::vector< iDynTree::SolidShape * >::value_type result; - - if (!SWIG_check_num_args("SolidShapesVector_pop",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_pop" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - try { - result = (std::vector< iDynTree::SolidShape * >::value_type)std_vector_Sl_iDynTree_SolidShape_Sm__Sg__pop(arg1); +int _wrap_new_FreeFloatingAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_FreeFloatingAcc__SWIG_0(resc,resv,argc,argv); } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_FreeFloatingAcc__SWIG_1(resc,resv,argc,argv); + } } - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_FreeFloatingAcc'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingAcc::FreeFloatingAcc()\n" + " iDynTree::FreeFloatingAcc::FreeFloatingAcc(iDynTree::Model const &)\n"); return 1; } -int _wrap_SolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::difference_type arg2 ; +int _wrap_FreeFloatingAcc_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("SolidShapesVector_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_brace" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_resize" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_brace" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::difference_type""'"); - } - arg2 = static_cast< std::vector< iDynTree::SolidShape * >::difference_type >(val2); - try { - result = (std::vector< iDynTree::SolidShape * >::value_type)std_vector_Sl_iDynTree_SolidShape_Sm__Sg__brace(arg1,arg2); + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "FreeFloatingAcc_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "FreeFloatingAcc_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59693,44 +62735,23 @@ int _wrap_SolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; - std::vector< iDynTree::SolidShape * >::difference_type arg3 ; +int _wrap_FreeFloatingAcc_baseAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; + iDynTree::SpatialAcc *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_setbrace",argc,3,3,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_baseAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); - } - arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SolidShapesVector_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::difference_type""'"); - } - arg3 = static_cast< std::vector< iDynTree::SolidShape * >::difference_type >(val3); - try { - std_vector_Sl_iDynTree_SolidShape_Sm__Sg__setbrace(arg1,arg2,arg3); - } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_baseAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); } - - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + result = (iDynTree::SpatialAcc *) &(arg1)->baseAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59738,30 +62759,23 @@ int _wrap_SolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SolidShapesVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_FreeFloatingAcc_jointAcc__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_append",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_jointAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_append" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_jointAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); - std_vector_Sl_iDynTree_SolidShape_Sm__Sg__append(arg1,arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &(arg1)->jointAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59769,16 +62783,23 @@ int _wrap_SolidShapesVector_append(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_new_SolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_FreeFloatingAcc_baseAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * > *result = 0 ; + iDynTree::SpatialAcc *result = 0 ; - if (!SWIG_check_num_args("new_SolidShapesVector",argc,0,0,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_baseAcc",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_baseAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + result = (iDynTree::SpatialAcc *) &((iDynTree::FreeFloatingAcc const *)arg1)->baseAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SpatialAcc, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59786,54 +62807,51 @@ int _wrap_new_SolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_SolidShapesVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = 0 ; - int res1 = SWIG_OLDOBJ ; - mxArray * _out; - std::vector< iDynTree::SolidShape * > *result = 0 ; - - if (!SWIG_check_num_args("new_SolidShapesVector",argc,1,1,0)) { - SWIG_fail; - } - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res1 = swig::asptr(argv[0], &ptr); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const &""'"); +int _wrap_FreeFloatingAcc_baseAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingAcc_baseAcc__SWIG_0(resc,resv,argc,argv); } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const &""'"); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingAcc_baseAcc__SWIG_1(resc,resv,argc,argv); } - arg1 = ptr; } - result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >((std::vector< iDynTree::SolidShape * > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res1)) delete arg1; - return 0; -fail: - if (SWIG_IsNewObj(res1)) delete arg1; + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingAcc_baseAcc'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingAcc::baseAcc()\n" + " iDynTree::FreeFloatingAcc::baseAcc() const\n"); return 1; } -int _wrap_SolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_FreeFloatingAcc_jointAcc__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_empty",argc,1,1,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_jointAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_empty" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_jointAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (bool)((std::vector< iDynTree::SolidShape * > const *)arg1)->empty(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *) &((iDynTree::FreeFloatingAcc const *)arg1)->jointAcc(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59841,57 +62859,51 @@ int _wrap_SolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SolidShapesVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::vector< iDynTree::SolidShape * >::size_type result; - - if (!SWIG_check_num_args("SolidShapesVector_size",argc,1,1,0)) { - SWIG_fail; +int _wrap_FreeFloatingAcc_jointAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingAcc_jointAcc__SWIG_0(resc,resv,argc,argv); + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_size" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_FreeFloatingAcc_jointAcc__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'FreeFloatingAcc_jointAcc'." + " Possible C/C++ prototypes are:\n" + " iDynTree::FreeFloatingAcc::jointAcc()\n" + " iDynTree::FreeFloatingAcc::jointAcc() const\n"); return 1; } -int _wrap_SolidShapesVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * > *arg2 = 0 ; +int _wrap_FreeFloatingAcc_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + unsigned int result; - if (!SWIG_check_num_args("SolidShapesVector_swap",argc,2,2,0)) { + if (!SWIG_check_num_args("FreeFloatingAcc_getNrOfDOFs",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_swap" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * > &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * > &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "FreeFloatingAcc_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc const *""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp2); - (arg1)->swap(*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + result = (unsigned int)((iDynTree::FreeFloatingAcc const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_unsigned_SS_int(static_cast< unsigned int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59899,24 +62911,26 @@ int _wrap_SolidShapesVector_swap(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_SolidShapesVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_delete_FreeFloatingAcc(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingAcc *arg1 = (iDynTree::FreeFloatingAcc *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("SolidShapesVector_begin",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_FreeFloatingAcc",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__FreeFloatingAcc, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_begin" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_FreeFloatingAcc" "', argument " "1"" of type '" "iDynTree::FreeFloatingAcc *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (arg1)->begin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59924,24 +62938,23 @@ int _wrap_SolidShapesVector_begin(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_ContactWrench_contactPoint__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::iterator result; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_end",argc,1,1,0)) { + if (!SWIG_check_num_args("ContactWrench_contactPoint",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_end" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactPoint" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (arg1)->end(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + result = (iDynTree::Position *) &(arg1)->contactPoint(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59949,24 +62962,23 @@ int _wrap_SolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_SolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_ContactWrench_contactWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::reverse_iterator result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_rbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("ContactWrench_contactWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (arg1)->rbegin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::reverse_iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + result = (iDynTree::Wrench *) &(arg1)->contactWrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59974,24 +62986,23 @@ int _wrap_SolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_ContactWrench_contactId(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::reverse_iterator result; + std::size_t *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_rend",argc,1,1,0)) { + if (!SWIG_check_num_args("ContactWrench_contactId",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_rend" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactId" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (arg1)->rend(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::reverse_iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + result = (std::size_t *) &(arg1)->contactId(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__size_t, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -59999,22 +63010,23 @@ int _wrap_SolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_SolidShapesVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_ContactWrench_contactPoint__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::Position *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_clear",argc,1,1,0)) { + if (!SWIG_check_num_args("ContactWrench_contactPoint",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_clear" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactPoint" "', argument " "1"" of type '" "iDynTree::ContactWrench const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - (arg1)->clear(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + result = (iDynTree::Position *) &((iDynTree::ContactWrench const *)arg1)->contactPoint(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Position, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60022,23 +63034,51 @@ int _wrap_SolidShapesVector_clear(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SolidShapesVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_ContactWrench_contactPoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ContactWrench_contactPoint__SWIG_0(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ContactWrench_contactPoint__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ContactWrench_contactPoint'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ContactWrench::contactPoint()\n" + " iDynTree::ContactWrench::contactPoint() const\n"); + return 1; +} + + +int _wrap_ContactWrench_contactWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - SwigValueWrapper< std::allocator< iDynTree::SolidShape * > > result; + iDynTree::Wrench *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_get_allocator",argc,1,1,0)) { + if (!SWIG_check_num_args("ContactWrench_contactWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ContactWrench_contactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->get_allocator(); - _out = SWIG_NewPointerObj((new std::vector< iDynTree::SolidShape * >::allocator_type(static_cast< const std::vector< iDynTree::SolidShape * >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__SolidShape_p_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + result = (iDynTree::Wrench *) &((iDynTree::ContactWrench const *)arg1)->contactWrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Wrench, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60046,23 +63086,44 @@ int _wrap_SolidShapesVector_get_allocator(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * >::size_type arg1 ; - size_t val1 ; - int ecode1 = 0 ; +int _wrap_ContactWrench_contactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ContactWrench_contactWrench__SWIG_0(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ContactWrench, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ContactWrench_contactWrench__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ContactWrench_contactWrench'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ContactWrench::contactWrench()\n" + " iDynTree::ContactWrench::contactWrench() const\n"); + return 1; +} + + +int _wrap_new_ContactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::vector< iDynTree::SolidShape * > *result = 0 ; + iDynTree::ContactWrench *result = 0 ; - if (!SWIG_check_num_args("new_SolidShapesVector",argc,1,1,0)) { + if (!SWIG_check_num_args("new_ContactWrench",argc,0,0,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); - } - arg1 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val1); - result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); + (void)argv; + result = (iDynTree::ContactWrench *)new iDynTree::ContactWrench(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60070,21 +63131,25 @@ int _wrap_new_SolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc, mxA } -int _wrap_SolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_delete_ContactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ContactWrench *arg1 = (iDynTree::ContactWrench *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SolidShapesVector_pop_back",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_ContactWrench",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ContactWrench, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ContactWrench" "', argument " "1"" of type '" "iDynTree::ContactWrench *""'"); + } + arg1 = reinterpret_cast< iDynTree::ContactWrench * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - (arg1)->pop_back(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -60093,30 +63158,23 @@ int _wrap_SolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::size_type arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; +int _wrap_new_LinkContactWrenches__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::size_t arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; + iDynTree::LinkContactWrenches *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("new_LinkContactWrenches",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "std::size_t""'"); } - arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = static_cast< std::size_t >(val1); + result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60124,38 +63182,16 @@ int _wrap_SolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_SolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::iterator arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; +int _wrap_new_LinkContactWrenches__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::vector< iDynTree::SolidShape * >::iterator result; + iDynTree::LinkContactWrenches *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_erase",argc,2,2,0)) { + if (!SWIG_check_num_args("new_LinkContactWrenches",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } - } - result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__erase__SWIG_0(arg1,arg2); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + (void)argv; + result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60163,52 +63199,26 @@ int _wrap_SolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, m } -int _wrap_SolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::iterator arg2 ; - std::vector< iDynTree::SolidShape * >::iterator arg3 ; - void *argp1 = 0 ; +int _wrap_new_LinkContactWrenches__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - swig::MatlabSwigIterator *iter3 = 0 ; - int res3 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::iterator result; + iDynTree::LinkContactWrenches *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_erase",argc,3,3,0)) { + if (!SWIG_check_num_args("new_LinkContactWrenches",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res3) || !iter3) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); - if (iter_t) { - arg3 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__erase__SWIG_1(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::LinkContactWrenches *)new iDynTree::LinkContactWrenches((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkContactWrenches, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60216,72 +63226,63 @@ int _wrap_SolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_SolidShapesVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_new_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinkContactWrenches__SWIG_1(resc,resv,argc,argv); + } + if (argc == 1) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); - if (_v) { - return _wrap_SolidShapesVector_erase__SWIG_0(resc,resv,argc,argv); - } + return _wrap_new_LinkContactWrenches__SWIG_2(resc,resv,argc,argv); } } - if (argc == 3) { + if (argc == 1) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); - if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); - if (_v) { - return _wrap_SolidShapesVector_erase__SWIG_1(resc,resv,argc,argv); - } - } + return _wrap_new_LinkContactWrenches__SWIG_0(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_erase'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinkContactWrenches'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::SolidShape * >::erase(std::vector< iDynTree::SolidShape * >::iterator)\n" - " std::vector< iDynTree::SolidShape * >::erase(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::iterator)\n"); + " iDynTree::LinkContactWrenches::LinkContactWrenches(std::size_t)\n" + " iDynTree::LinkContactWrenches::LinkContactWrenches()\n" + " iDynTree::LinkContactWrenches::LinkContactWrenches(iDynTree::Model const &)\n"); return 1; } -int _wrap_new_SolidShapesVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * >::size_type arg1 ; - std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; - size_t val1 ; - int ecode1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; +int _wrap_LinkContactWrenches_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + std::size_t arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * > *result = 0 ; - if (!SWIG_check_num_args("new_SolidShapesVector",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_resize",argc,2,2,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); - } - arg1 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SolidShapesVector" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); - result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "std::size_t""'"); + } + arg2 = static_cast< std::size_t >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60289,78 +63290,104 @@ int _wrap_new_SolidShapesVector__SWIG_3(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_SolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SolidShapesVector__SWIG_0(resc,resv,argc,argv); +int _wrap_LinkContactWrenches_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinkContactWrenches_resize",argc,2,2,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_SolidShapesVector__SWIG_2(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_resize" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); } - if (argc == 1) { + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinkContactWrenches_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SolidShapesVector__SWIG_1(resc,resv,argc,argv); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinkContactWrenches_resize__SWIG_1(resc,resv,argc,argv); + } } } if (argc == 2) { int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); + _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_SolidShapesVector__SWIG_3(resc,resv,argc,argv); + return _wrap_LinkContactWrenches_resize__SWIG_0(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SolidShapesVector'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkContactWrenches_resize'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::SolidShape * >::vector()\n" - " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * > const &)\n" - " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * >::size_type)\n" - " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); + " iDynTree::LinkContactWrenches::resize(std::size_t)\n" + " iDynTree::LinkContactWrenches::resize(iDynTree::Model const &)\n"); return 1; } -int _wrap_SolidShapesVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_LinkContactWrenches_getNrOfContactsForLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + size_t result; - if (!SWIG_check_num_args("SolidShapesVector_push_back",argc,2,2,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_getNrOfContactsForLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); - } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_getNrOfContactsForLink" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); } - arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); - (arg1)->push_back(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_getNrOfContactsForLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = ((iDynTree::LinkContactWrenches const *)arg1)->getNrOfContactsForLink(arg2); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60368,23 +63395,38 @@ int _wrap_SolidShapesVector_push_back(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_SolidShapesVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_LinkContactWrenches_setNrOfContactsForLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; + size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("SolidShapesVector_front",argc,1,1,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_setNrOfContactsForLink",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_front" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (std::vector< iDynTree::SolidShape * >::value_type)((std::vector< iDynTree::SolidShape * > const *)arg1)->front(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_setNrOfContactsForLink" "', argument " "3"" of type '" "size_t""'"); + } + arg3 = static_cast< size_t >(val3); + (arg1)->setNrOfContactsForLink(arg2,arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60392,23 +63434,23 @@ int _wrap_SolidShapesVector_front(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_SolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; +int _wrap_LinkContactWrenches_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::value_type result; + size_t result; - if (!SWIG_check_num_args("SolidShapesVector_back",argc,1,1,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_getNrOfLinks",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = (std::vector< iDynTree::SolidShape * >::value_type)((std::vector< iDynTree::SolidShape * > const *)arg1)->back(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + result = ((iDynTree::LinkContactWrenches const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60416,38 +63458,39 @@ int _wrap_SolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_SolidShapesVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::size_type arg2 ; - std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_LinkContactWrenches_contactWrench__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; + size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; + iDynTree::ContactWrench *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_assign",argc,3,3,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_contactWrench",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_assign" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_contactWrench" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_assign" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_contactWrench" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); - } - arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); - (arg1)->assign(arg2,arg3); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_contactWrench" "', argument " "3"" of type '" "size_t""'"); + } + arg3 = static_cast< size_t >(val3); + result = (iDynTree::ContactWrench *) &(arg1)->contactWrench(arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60455,38 +63498,39 @@ int _wrap_SolidShapesVector_assign(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SolidShapesVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::size_type arg2 ; - std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_LinkContactWrenches_contactWrench__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::LinkIndex arg2 ; + size_t arg3 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; - void *argp3 = 0 ; - int res3 = 0 ; + size_t val3 ; + int ecode3 = 0 ; mxArray * _out; + iDynTree::ContactWrench *result = 0 ; - if (!SWIG_check_num_args("SolidShapesVector_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_contactWrench",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_contactWrench" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkContactWrenches_contactWrench" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); - } - arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); - (arg1)->resize(arg2,arg3); - _out = (mxArray*)0; + arg2 = static_cast< iDynTree::LinkIndex >(val2); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinkContactWrenches_contactWrench" "', argument " "3"" of type '" "size_t""'"); + } + arg3 = static_cast< size_t >(val3); + result = (iDynTree::ContactWrench *) &((iDynTree::LinkContactWrenches const *)arg1)->contactWrench(arg2,arg3); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ContactWrench, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60494,89 +63538,86 @@ int _wrap_SolidShapesVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_SolidShapesVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { +int _wrap_LinkContactWrenches_contactWrench(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - return _wrap_SolidShapesVector_resize__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinkContactWrenches_contactWrench__SWIG_0(resc,resv,argc,argv); + } } } } if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__LinkContactWrenches, 0); _v = SWIG_CheckState(res); if (_v) { { - int res = SWIG_AsVal_size_t(argv[1], NULL); + int res = SWIG_AsVal_ptrdiff_t(argv[1], NULL); _v = SWIG_CheckState(res); } if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_SolidShapesVector_resize__SWIG_1(resc,resv,argc,argv); + return _wrap_LinkContactWrenches_contactWrench__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinkContactWrenches_contactWrench'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::SolidShape * >::resize(std::vector< iDynTree::SolidShape * >::size_type)\n" - " std::vector< iDynTree::SolidShape * >::resize(std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); + " iDynTree::LinkContactWrenches::contactWrench(iDynTree::LinkIndex const,size_t const)\n" + " iDynTree::LinkContactWrenches::contactWrench(iDynTree::LinkIndex const,size_t const) const\n"); return 1; } -int _wrap_SolidShapesVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::iterator arg2 ; - std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_LinkContactWrenches_computeNetWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::LinkNetExternalWrenches *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - void *argp3 = 0 ; - int res3 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::iterator result; + bool result; - if (!SWIG_check_num_args("SolidShapesVector_insert",argc,3,3,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_computeNetWrenches",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "2"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); } - res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_computeNetWrenches" "', argument " "2"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); } - arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); - result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__insert__SWIG_0(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg2 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp2); + result = (bool)((iDynTree::LinkContactWrenches const *)arg1)->computeNetWrenches(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60584,51 +63625,177 @@ int _wrap_SolidShapesVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_SolidShapesVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::iterator arg2 ; - std::vector< iDynTree::SolidShape * >::size_type arg3 ; - std::vector< iDynTree::SolidShape * >::value_type arg4 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; +int _wrap_LinkContactWrenches_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - size_t val3 ; - int ecode3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("SolidShapesVector_insert",argc,4,4,0)) { + if (!SWIG_check_num_args("LinkContactWrenches_toString",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkContactWrenches_toString" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches const *""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); - } else { - swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkContactWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkContactWrenches_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::LinkContactWrenches const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_LinkContactWrenches(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::LinkContactWrenches *arg1 = (iDynTree::LinkContactWrenches *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_LinkContactWrenches",argc,1,1,0)) { + SWIG_fail; + } + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkContactWrenches, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkContactWrenches" "', argument " "1"" of type '" "iDynTree::LinkContactWrenches *""'"); + } + arg1 = reinterpret_cast< iDynTree::LinkContactWrenches * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_getRandomLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::Link result; + + if (!SWIG_check_num_args("getRandomLink",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = iDynTree::getRandomLink(); + _out = SWIG_NewPointerObj((new iDynTree::Link(static_cast< const iDynTree::Link& >(result))), SWIGTYPE_p_iDynTree__Link, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_addRandomLinkToModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::string arg2 ; + std::string arg3 ; + bool arg4 ; + void *argp1 = 0 ; + int res1 = 0 ; + bool val4 ; + int ecode4 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("addRandomLinkToModel",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "2"" of type '" "std::string""'"); } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; } - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "3"" of type '" "std::string""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + ecode4 = SWIG_AsVal_bool(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "addRandomLinkToModel" "', argument " "4"" of type '" "bool""'"); } - arg3 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val3); - res4 = SWIG_ConvertPtr(argv[3], &argp4,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + arg4 = static_cast< bool >(val4); + iDynTree::addRandomLinkToModel(*arg1,arg2,arg3,arg4); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_addRandomLinkToModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::string arg2 ; + std::string arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("addRandomLinkToModel",argc,3,3,0)) { + SWIG_fail; } - arg4 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp4); - std_vector_Sl_iDynTree_SolidShape_Sm__Sg__insert__SWIG_1(arg1,arg2,arg3,arg4); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomLinkToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "2"" of type '" "std::string""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomLinkToModel" "', argument " "3"" of type '" "std::string""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + iDynTree::addRandomLinkToModel(*arg1,arg2,arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -60637,81 +63804,94 @@ int _wrap_SolidShapesVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_SolidShapesVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_addRandomLinkToModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 3) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_SolidShapesVector_insert__SWIG_0(resc,resv,argc,argv); + return _wrap_addRandomLinkToModel__SWIG_1(resc,resv,argc,argv); } } } } if (argc == 4) { int _v; - int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_bool(argv[3], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_SolidShapesVector_insert__SWIG_1(resc,resv,argc,argv); + return _wrap_addRandomLinkToModel__SWIG_0(resc,resv,argc,argv); } } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_insert'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'addRandomLinkToModel'." " Possible C/C++ prototypes are:\n" - " std::vector< iDynTree::SolidShape * >::insert(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::value_type)\n" - " std::vector< iDynTree::SolidShape * >::insert(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); + " iDynTree::addRandomLinkToModel(iDynTree::Model &,std::string,std::string,bool)\n" + " iDynTree::addRandomLinkToModel(iDynTree::Model &,std::string,std::string)\n"); return 1; } -int _wrap_SolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - std::vector< iDynTree::SolidShape * >::size_type arg2 ; +int _wrap_addRandomAdditionalFrameToModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::string arg2 ; + std::string arg3 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("SolidShapesVector_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("addRandomAdditionalFrameToModel",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "addRandomAdditionalFrameToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); - } - arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); - (arg1)->reserve(arg2); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "addRandomAdditionalFrameToModel" "', argument " "1"" of type '" "iDynTree::Model &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomAdditionalFrameToModel" "', argument " "2"" of type '" "std::string""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "addRandomAdditionalFrameToModel" "', argument " "3"" of type '" "std::string""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + iDynTree::addRandomAdditionalFrameToModel(*arg1,arg2,arg3); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -60720,23 +63900,26 @@ int _wrap_SolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SolidShapesVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - void *argp1 = 0 ; +int _wrap_getRandomLinkIndexOfModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - std::vector< iDynTree::SolidShape * >::size_type result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("SolidShapesVector_capacity",argc,1,1,0)) { + if (!SWIG_check_num_args("getRandomLinkIndexOfModel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomLinkIndexOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->capacity(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomLinkIndexOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = iDynTree::getRandomLinkIndexOfModel((iDynTree::Model const &)*arg1); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60744,26 +63927,26 @@ int _wrap_SolidShapesVector_capacity(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_delete_SolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; - void *argp1 = 0 ; +int _wrap_getRandomLinkOfModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; + std::string result; - int is_owned; - if (!SWIG_check_num_args("delete_SolidShapesVector",argc,1,1,0)) { + if (!SWIG_check_num_args("getRandomLinkOfModel",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomLinkOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomLinkOfModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = iDynTree::getRandomLinkOfModel((iDynTree::Model const &)*arg1); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60771,29 +63954,23 @@ int _wrap_delete_SolidShapesVector(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_LinksSolidShapesVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_int2string(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + int arg1 ; + int val1 ; + int ecode1 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type result; + std::string result; - if (!SWIG_check_num_args("LinksSolidShapesVector_pop",argc,1,1,0)) { + if (!SWIG_check_num_args("int2string",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_pop" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - try { - result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__pop(arg1); - } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); - } - - _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(result)); + ecode1 = SWIG_AsVal_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "int2string" "', argument " "1"" of type '" "int""'"); + } + arg1 = static_cast< int >(val1); + result = iDynTree::int2string(arg1); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60801,37 +63978,31 @@ int _wrap_LinksSolidShapesVector_pop(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinksSolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::difference_type arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; +int _wrap_getRandomModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + unsigned int arg1 ; + size_t arg2 ; + unsigned int val1 ; + int ecode1 = 0 ; + size_t val2 ; int ecode2 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type result; + iDynTree::Model result; - if (!SWIG_check_num_args("LinksSolidShapesVector_brace",argc,2,2,0)) { + if (!SWIG_check_num_args("getRandomModel",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_brace" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomModel" "', argument " "1"" of type '" "unsigned int""'"); + } + arg1 = static_cast< unsigned int >(val1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_brace" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomModel" "', argument " "2"" of type '" "size_t""'"); } - arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::difference_type >(val2); - try { - result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__brace(arg1,arg2); - } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); - } - - _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(result)); + arg2 = static_cast< size_t >(val2); + result = iDynTree::getRandomModel(arg1,arg2); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60839,46 +64010,99 @@ int _wrap_LinksSolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_LinksSolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::difference_type arg3 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; +int _wrap_getRandomModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + unsigned int arg1 ; + unsigned int val1 ; + int ecode1 = 0 ; mxArray * _out; + iDynTree::Model result; - if (!SWIG_check_num_args("LinksSolidShapesVector_setbrace",argc,3,3,0)) { + if (!SWIG_check_num_args("getRandomModel",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomModel" "', argument " "1"" of type '" "unsigned int""'"); + } + arg1 = static_cast< unsigned int >(val1); + result = iDynTree::getRandomModel(arg1); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_getRandomModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_getRandomModel__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - int res = swig::asptr(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type""'"); + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_getRandomModel__SWIG_0(resc,resv,argc,argv); + } } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'getRandomModel'." + " Possible C/C++ prototypes are:\n" + " iDynTree::getRandomModel(unsigned int,size_t)\n" + " iDynTree::getRandomModel(unsigned int)\n"); + return 1; +} + + +int _wrap_getRandomChain__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + unsigned int arg1 ; + size_t arg2 ; + bool arg3 ; + unsigned int val1 ; + int ecode1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + bool val3 ; + int ecode3 = 0 ; + mxArray * _out; + iDynTree::Model result; + + if (!SWIG_check_num_args("getRandomChain",argc,3,3,0)) { + SWIG_fail; + } + ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); + } + arg1 = static_cast< unsigned int >(val1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomChain" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + ecode3 = SWIG_AsVal_bool(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::difference_type""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "getRandomChain" "', argument " "3"" of type '" "bool""'"); } - arg3 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::difference_type >(val3); - try { - std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__setbrace(arg1,arg2,arg3); - } - catch(std::out_of_range &_e) { - SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); - } - - _out = (mxArray*)0; + arg3 = static_cast< bool >(val3); + result = iDynTree::getRandomChain(arg1,arg2,arg3); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60886,32 +64110,31 @@ int _wrap_LinksSolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, m } -int _wrap_LinksSolidShapesVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_getRandomChain__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + unsigned int arg1 ; + size_t arg2 ; + unsigned int val1 ; + int ecode1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; + iDynTree::Model result; - if (!SWIG_check_num_args("LinksSolidShapesVector_append",argc,2,2,0)) { + if (!SWIG_check_num_args("getRandomChain",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_append" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - int res = swig::asptr(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "LinksSolidShapesVector_append" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__append(arg1,arg2); - _out = (mxArray*)0; + ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); + } + arg1 = static_cast< unsigned int >(val1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "getRandomChain" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = iDynTree::getRandomChain(arg1,arg2); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60919,16 +64142,23 @@ int _wrap_LinksSolidShapesVector_append(int resc, mxArray *resv[], int argc, mxA } -int _wrap_new_LinksSolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_getRandomChain__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + unsigned int arg1 ; + unsigned int val1 ; + int ecode1 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; + iDynTree::Model result; - if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,0,0,0)) { + if (!SWIG_check_num_args("getRandomChain",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); + ecode1 = SWIG_AsVal_unsigned_SS_int(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getRandomChain" "', argument " "1"" of type '" "unsigned int""'"); + } + arg1 = static_cast< unsigned int >(val1); + result = iDynTree::getRandomChain(arg1); + _out = SWIG_NewPointerObj((new iDynTree::Model(static_cast< const iDynTree::Model& >(result))), SWIGTYPE_p_iDynTree__Model, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -60936,53 +64166,154 @@ int _wrap_new_LinksSolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc } -int _wrap_new_LinksSolidShapesVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *arg1 = 0 ; - int res1 = SWIG_OLDOBJ ; +int _wrap_getRandomChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_getRandomChain__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_getRandomChain__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + { + int res = SWIG_AsVal_unsigned_SS_int(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + { + int res = SWIG_AsVal_bool(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_getRandomChain__SWIG_0(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'getRandomChain'." + " Possible C/C++ prototypes are:\n" + " iDynTree::getRandomChain(unsigned int,size_t,bool)\n" + " iDynTree::getRandomChain(unsigned int,size_t)\n" + " iDynTree::getRandomChain(unsigned int)\n"); + return 1; +} + + +int _wrap_getRandomJointPositions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::VectorDynSize *arg1 = 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; - if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,1,1,0)) { + if (!SWIG_check_num_args("getRandomJointPositions",argc,2,2,0)) { SWIG_fail; } - { - std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > *ptr = (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > *)0; - res1 = swig::asptr(argv[0], &ptr); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &""'"); - } - arg1 = ptr; + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomJointPositions" "', argument " "1"" of type '" "iDynTree::VectorDynSize &""'"); } - result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >((std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomJointPositions" "', argument " "1"" of type '" "iDynTree::VectorDynSize &""'"); + } + arg1 = reinterpret_cast< iDynTree::VectorDynSize * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "getRandomJointPositions" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomJointPositions" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + iDynTree::getRandomJointPositions(*arg1,(iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res1)) delete arg1; return 0; fail: - if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_LinksSolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_getRandomInverseDynamicsInputs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::FreeFloatingPos *arg1 = 0 ; + iDynTree::FreeFloatingVel *arg2 = 0 ; + iDynTree::FreeFloatingAcc *arg3 = 0 ; + iDynTree::LinkNetExternalWrenches *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_empty",argc,1,1,0)) { + if (!SWIG_check_num_args("getRandomInverseDynamicsInputs",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_empty" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "getRandomInverseDynamicsInputs" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (bool)((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->empty(); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "1"" of type '" "iDynTree::FreeFloatingPos &""'"); + } + arg1 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "getRandomInverseDynamicsInputs" "', argument " "2"" of type '" "iDynTree::FreeFloatingVel &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "2"" of type '" "iDynTree::FreeFloatingVel &""'"); + } + arg2 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "getRandomInverseDynamicsInputs" "', argument " "3"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "3"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "getRandomInverseDynamicsInputs" "', argument " "4"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "getRandomInverseDynamicsInputs" "', argument " "4"" of type '" "iDynTree::LinkNetExternalWrenches &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp4); + result = (bool)iDynTree::getRandomInverseDynamicsInputs(*arg1,*arg2,*arg3,*arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -60991,23 +64322,37 @@ int _wrap_LinksSolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_LinksSolidShapesVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; +int _wrap_removeFakeLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type result; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_size",argc,1,1,0)) { + if (!SWIG_check_num_args("removeFakeLinks",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_size" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "removeFakeLinks" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->size(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "removeFakeLinks" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "removeFakeLinks" "', argument " "2"" of type '" "iDynTree::Model &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "removeFakeLinks" "', argument " "2"" of type '" "iDynTree::Model &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)iDynTree::removeFakeLinks((iDynTree::Model const &)*arg1,*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61015,83 +64360,154 @@ int _wrap_LinksSolidShapesVector_size(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinksSolidShapesVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_createReducedModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg2 = 0 ; + iDynTree::Model *arg3 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + int res2 = SWIG_OLDOBJ ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_swap",argc,2,2,0)) { + if (!SWIG_check_num_args("createReducedModel",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_swap" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "createReducedModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinksSolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > &""'"); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res2 = swig::asptr(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "createReducedModel" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg2 = ptr; } - arg2 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > * >(argp2); - (arg1)->swap(*arg2); - _out = (mxArray*)0; + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "createReducedModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createReducedModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + arg3 = reinterpret_cast< iDynTree::Model * >(argp3); + result = (bool)iDynTree::createReducedModel((iDynTree::Model const &)*arg1,(std::vector< std::string,std::allocator< std::string > > const &)*arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_LinksSolidShapesVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; +int _wrap_createModelWithNormalizedJointNumbering(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::string *arg2 = 0 ; + iDynTree::Model *arg3 = 0 ; + void *argp1 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_begin",argc,1,1,0)) { + if (!SWIG_check_num_args("createModelWithNormalizedJointNumbering",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_begin" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (arg1)->begin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "createModelWithNormalizedJointNumbering" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "createModelWithNormalizedJointNumbering" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + arg3 = reinterpret_cast< iDynTree::Model * >(argp3); + result = (bool)iDynTree::createModelWithNormalizedJointNumbering((iDynTree::Model const &)*arg1,(std::string const &)*arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_LinksSolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; +int _wrap_extractSubModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::Model *arg3 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_end",argc,1,1,0)) { + if (!SWIG_check_num_args("extractSubModel",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_end" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "extractSubModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (arg1)->end(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "extractSubModel" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "extractSubModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "extractSubModel" "', argument " "3"" of type '" "iDynTree::Model &""'"); + } + arg3 = reinterpret_cast< iDynTree::Model * >(argp3); + result = (bool)iDynTree::extractSubModel((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61099,24 +64515,16 @@ int _wrap_LinksSolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_LinksSolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator result; + iDynTree::SubModelDecomposition *result = 0 ; - if (!SWIG_check_num_args("LinksSolidShapesVector_rbegin",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SubModelDecomposition",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_rbegin" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (arg1)->rbegin(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + (void)argv; + result = (iDynTree::SubModelDecomposition *)new iDynTree::SubModelDecomposition(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SubModelDecomposition, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61124,24 +64532,26 @@ int _wrap_LinksSolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxA } -int _wrap_LinksSolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_delete_SubModelDecomposition(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator result; - if (!SWIG_check_num_args("LinksSolidShapesVector_rend",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SubModelDecomposition",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_rend" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SubModelDecomposition" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (arg1)->rend(); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61149,70 +64559,91 @@ int _wrap_LinksSolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinksSolidShapesVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SubModelDecomposition_splitModelAlongJoints(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + iDynTree::Model *arg2 = 0 ; + iDynTree::Traversal *arg3 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + int res4 = SWIG_OLDOBJ ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_clear",argc,1,1,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_splitModelAlongJoints",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_clear" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - (arg1)->clear(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res4 = swig::asptr(argv[3], &ptr); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_splitModelAlongJoints" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg4 = ptr; + } + result = (bool)(arg1)->splitModelAlongJoints((iDynTree::Model const &)*arg2,(iDynTree::Traversal const &)*arg3,(std::vector< std::string,std::allocator< std::string > > const &)*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: + if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_LinksSolidShapesVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SubModelDecomposition_setNrOfSubModels(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - SwigValueWrapper< std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > result; - if (!SWIG_check_num_args("LinksSolidShapesVector_get_allocator",argc,1,1,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_setNrOfSubModels",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_get_allocator" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->get_allocator(); - _out = SWIG_NewPointerObj((new std::vector< std::vector< iDynTree::SolidShape * > >::allocator_type(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_LinksSolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg1 ; - size_t val1 ; - int ecode1 = 0 ; - mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; - - if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,1,1,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_setNrOfSubModels" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_setNrOfSubModels" "', argument " "2"" of type '" "size_t""'"); } - arg1 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val1); - result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); + arg2 = static_cast< size_t >(val2); + (arg1)->setNrOfSubModels(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61220,22 +64651,23 @@ int _wrap_new_LinksSolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc } -int _wrap_LinksSolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SubModelDecomposition_getNrOfSubModels(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + size_t result; - if (!SWIG_check_num_args("LinksSolidShapesVector_pop_back",argc,1,1,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getNrOfSubModels",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_pop_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getNrOfSubModels" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - (arg1)->pop_back(); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + result = ((iDynTree::SubModelDecomposition const *)arg1)->getNrOfSubModels(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61243,30 +64675,23 @@ int _wrap_LinksSolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, m } -int _wrap_LinksSolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; +int _wrap_SubModelDecomposition_getNrOfLinks(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + size_t result; - if (!SWIG_check_num_args("LinksSolidShapesVector_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getNrOfLinks",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getNrOfLinks" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); - } - arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); - (arg1)->resize(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + result = ((iDynTree::SubModelDecomposition const *)arg1)->getNrOfLinks(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61274,38 +64699,31 @@ int _wrap_LinksSolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int a } -int _wrap_LinksSolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; +int _wrap_SubModelDecomposition_getTraversal__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; + iDynTree::Traversal *result = 0 ; - if (!SWIG_check_num_args("LinksSolidShapesVector_erase",argc,2,2,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getTraversal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } else { - swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getTraversal" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition *""'"); } - result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__erase__SWIG_0(arg1,arg2); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getTraversal" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::Traversal *) &(arg1)->getTraversal(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Traversal, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61313,52 +64731,31 @@ int _wrap_LinksSolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int ar } -int _wrap_LinksSolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg3 ; +int _wrap_SubModelDecomposition_getTraversal__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - swig::MatlabSwigIterator *iter3 = 0 ; - int res3 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; + iDynTree::Traversal *result = 0 ; - if (!SWIG_check_num_args("LinksSolidShapesVector_erase",argc,3,3,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getTraversal",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } else { - swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } - } - res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res3) || !iter3) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } else { - swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter3); - if (iter_t) { - arg3 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getTraversal" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); } - result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__erase__SWIG_1(arg1,arg2,arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getTraversal" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::Traversal *) &((iDynTree::SubModelDecomposition const *)arg1)->getTraversal(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Traversal, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61366,188 +64763,118 @@ int _wrap_LinksSolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int ar } -int _wrap_LinksSolidShapesVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_SubModelDecomposition_getTraversal(int resc, mxArray *resv[], int argc, mxArray *argv[]) { if (argc == 2) { int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0); _v = SWIG_CheckState(res); if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); - if (_v) { - return _wrap_LinksSolidShapesVector_erase__SWIG_0(resc,resv,argc,argv); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); } - } - } - if (argc == 3) { - int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); - if (_v) { - return _wrap_LinksSolidShapesVector_erase__SWIG_1(resc,resv,argc,argv); - } + return _wrap_SubModelDecomposition_getTraversal__SWIG_0(resc,resv,argc,argv); } } } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_erase'." - " Possible C/C++ prototypes are:\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::erase(std::vector< std::vector< iDynTree::SolidShape * > >::iterator)\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::erase(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::iterator)\n"); - return 1; -} - - -int _wrap_new_LinksSolidShapesVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg1 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg2 = 0 ; - size_t val1 ; - int ecode1 = 0 ; - int res2 = SWIG_OLDOBJ ; - mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; - - if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,2,2,0)) { - SWIG_fail; - } - ecode1 = SWIG_AsVal_size_t(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); - } - arg1 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val1); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res2 = swig::asptr(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_LinksSolidShapesVector" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinksSolidShapesVector" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - arg2 = ptr; - } - result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(arg1,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - return 0; -fail: - if (SWIG_IsNewObj(res2)) delete arg2; - return 1; -} - - -int _wrap_new_LinksSolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_LinksSolidShapesVector__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_new_LinksSolidShapesVector__SWIG_2(resc,resv,argc,argv); - } - } - if (argc == 1) { - int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_LinksSolidShapesVector__SWIG_1(resc,resv,argc,argv); - } - } if (argc == 2) { int _v; - { - int res = SWIG_AsVal_size_t(argv[0], NULL); - _v = SWIG_CheckState(res); - } + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0); + _v = SWIG_CheckState(res); if (_v) { - int res = swig::asptr(argv[1], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); - _v = SWIG_CheckState(res); + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } if (_v) { - return _wrap_new_LinksSolidShapesVector__SWIG_3(resc,resv,argc,argv); + return _wrap_SubModelDecomposition_getTraversal__SWIG_1(resc,resv,argc,argv); } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinksSolidShapesVector'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SubModelDecomposition_getTraversal'." " Possible C/C++ prototypes are:\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::vector()\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &)\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape * > >::size_type)\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); + " iDynTree::SubModelDecomposition::getTraversal(size_t const)\n" + " iDynTree::SubModelDecomposition::getTraversal(size_t const) const\n"); return 1; } -int _wrap_LinksSolidShapesVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg2 = 0 ; +int _wrap_SubModelDecomposition_getSubModelOfLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + iDynTree::LinkIndex temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + size_t result; - if (!SWIG_check_num_args("LinksSolidShapesVector_push_back",argc,2,2,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getSubModelOfLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_push_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res2 = swig::asptr(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinksSolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - arg2 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getSubModelOfLink" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); } - (arg1)->push_back((std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SubModelDecomposition_getSubModelOfLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = ((iDynTree::SubModelDecomposition const *)arg1)->getSubModelOfLink((iDynTree::LinkIndex const &)*arg2); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_LinksSolidShapesVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SubModelDecomposition_getSubModelOfFrame(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SubModelDecomposition *arg1 = (iDynTree::SubModelDecomposition *) 0 ; + iDynTree::Model *arg2 = 0 ; + iDynTree::FrameIndex *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + iDynTree::FrameIndex temp3 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *result = 0 ; + size_t result; - if (!SWIG_check_num_args("LinksSolidShapesVector_front",argc,1,1,0)) { + if (!SWIG_check_num_args("SubModelDecomposition_getSubModelOfFrame",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_front" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "1"" of type '" "iDynTree::SubModelDecomposition const *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (std::vector< std::vector< iDynTree::SolidShape * > >::value_type *) &((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->front(); - _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(*result)); + arg1 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SubModelDecomposition_getSubModelOfFrame" "', argument " "3"" of type '" "iDynTree::FrameIndex""'"); + } + temp3 = static_cast< iDynTree::FrameIndex >(val3); + arg3 = &temp3; + result = ((iDynTree::SubModelDecomposition const *)arg1)->getSubModelOfFrame((iDynTree::Model const &)*arg2,(iDynTree::FrameIndex const &)*arg3); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61555,23 +64882,58 @@ int _wrap_LinksSolidShapesVector_front(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_LinksSolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - void *argp1 = 0 ; +int _wrap_computeTransformToTraversalBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::JointPosDoubleArray *arg3 = 0 ; + iDynTree::LinkPositions *arg4 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *result = 0 ; - if (!SWIG_check_num_args("LinksSolidShapesVector_back",argc,1,1,0)) { + if (!SWIG_check_num_args("computeTransformToTraversalBase",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "computeTransformToTraversalBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = (std::vector< std::vector< iDynTree::SolidShape * > >::value_type *) &((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->back(); - _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(*result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "computeTransformToTraversalBase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "computeTransformToTraversalBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "computeTransformToTraversalBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToTraversalBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); + iDynTree::computeTransformToTraversalBase((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61579,328 +64941,300 @@ int _wrap_LinksSolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_LinksSolidShapesVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_computeTransformToSubModelBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::SubModelDecomposition *arg2 = 0 ; + iDynTree::JointPosDoubleArray *arg3 = 0 ; + iDynTree::LinkPositions *arg4 = 0 ; + void *argp1 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - int res3 = SWIG_OLDOBJ ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("LinksSolidShapesVector_assign",argc,3,3,0)) { + if (!SWIG_check_num_args("computeTransformToSubModelBase",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_assign" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "computeTransformToSubModelBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_assign" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); - } - arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res3 = swig::asptr(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - arg3 = ptr; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - (arg1)->assign(arg2,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg3); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SubModelDecomposition, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "computeTransformToSubModelBase" "', argument " "2"" of type '" "iDynTree::SubModelDecomposition const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "2"" of type '" "iDynTree::SubModelDecomposition const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SubModelDecomposition * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "computeTransformToSubModelBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "computeTransformToSubModelBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "computeTransformToSubModelBase" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); + iDynTree::computeTransformToSubModelBase((iDynTree::Model const &)*arg1,(iDynTree::SubModelDecomposition const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_LinksSolidShapesVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_new_SixAxisForceTorqueSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::SixAxisForceTorqueSensor *result = 0 ; + + if (!SWIG_check_num_args("new_SixAxisForceTorqueSensor",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::SixAxisForceTorqueSensor *)new iDynTree::SixAxisForceTorqueSensor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_SixAxisForceTorqueSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - int res3 = SWIG_OLDOBJ ; mxArray * _out; + iDynTree::SixAxisForceTorqueSensor *result = 0 ; - if (!SWIG_check_num_args("LinksSolidShapesVector_resize",argc,3,3,0)) { + if (!SWIG_check_num_args("new_SixAxisForceTorqueSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const &""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); - } - arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res3 = swig::asptr(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - arg3 = ptr; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const &""'"); } - (arg1)->resize(arg2,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg3); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = (iDynTree::SixAxisForceTorqueSensor *)new iDynTree::SixAxisForceTorqueSensor((iDynTree::SixAxisForceTorqueSensor const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_LinksSolidShapesVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_LinksSolidShapesVector_resize__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_new_SixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SixAxisForceTorqueSensor__SWIG_0(resc,resv,argc,argv); } - if (argc == 3) { + if (argc == 1) { int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - int res = swig::asptr(argv[2], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinksSolidShapesVector_resize__SWIG_1(resc,resv,argc,argv); - } - } + return _wrap_new_SixAxisForceTorqueSensor__SWIG_1(resc,resv,argc,argv); } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_resize'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SixAxisForceTorqueSensor'." " Possible C/C++ prototypes are:\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::resize(std::vector< std::vector< iDynTree::SolidShape * > >::size_type)\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::resize(std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); + " iDynTree::SixAxisForceTorqueSensor::SixAxisForceTorqueSensor()\n" + " iDynTree::SixAxisForceTorqueSensor::SixAxisForceTorqueSensor(iDynTree::SixAxisForceTorqueSensor const &)\n"); return 1; } -int _wrap_LinksSolidShapesVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; +int _wrap_delete_SixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - int res3 = SWIG_OLDOBJ ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("LinksSolidShapesVector_insert",argc,3,3,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SixAxisForceTorqueSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } else { - swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SixAxisForceTorqueSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setName",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res3 = swig::asptr(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); } - arg3 = ptr; + arg2 = ptr; } - result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_0(arg1,arg2,(std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > const &)*arg3); - _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), - swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + result = (bool)(arg1)->setName((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_LinksSolidShapesVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg3 ; - std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg4 = 0 ; +int _wrap_SixAxisForceTorqueSensor_setFirstLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Transform *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - swig::MatlabSwigIterator *iter2 = 0 ; - int res2 ; - size_t val3 ; - int ecode3 = 0 ; - int res4 = SWIG_OLDOBJ ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("LinksSolidShapesVector_insert",argc,4,4,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setFirstLinkSensorTransform",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); - } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); - if (!SWIG_IsOK(res2) || !iter2) { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } else { - swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); - if (iter_t) { - arg2 = iter_t->get_current(); - } else { - SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); - } + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg3 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val3); - { - std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; - res4 = swig::asptr(argv[3], &ptr); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "LinksSolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); - } - arg4 = ptr; + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); } - std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_1(arg1,arg2,arg3,(std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > const &)*arg4); - _out = (mxArray*)0; + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->setFirstLinkSensorTransform(arg2,(iDynTree::Transform const &)*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: - if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_LinksSolidShapesVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); - if (_v) { - int res = swig::asptr(argv[2], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinksSolidShapesVector_insert__SWIG_0(resc,resv,argc,argv); - } - } - } +int _wrap_SixAxisForceTorqueSensor_setSecondLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Transform *arg3 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setSecondLinkSensorTransform",argc,3,3,0)) { + SWIG_fail; } - if (argc == 4) { - int _v; - int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - swig::MatlabSwigIterator *iter = 0; - int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); - _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - int res = swig::asptr(argv[3], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_LinksSolidShapesVector_insert__SWIG_1(resc,resv,argc,argv); - } - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_insert'." - " Possible C/C++ prototypes are:\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::insert(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n" - " std::vector< std::vector< iDynTree::SolidShape * > >::insert(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->setSecondLinkSensorTransform(arg2,(iDynTree::Transform const &)*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_LinksSolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; +int _wrap_SixAxisForceTorqueSensor_getFirstLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("LinksSolidShapesVector_reserve",argc,2,2,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getFirstLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_reserve" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getFirstLinkIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_reserve" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); - } - arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); - (arg1)->reserve(arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getFirstLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61908,23 +65242,23 @@ int _wrap_LinksSolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mx } -int _wrap_LinksSolidShapesVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SixAxisForceTorqueSensor_getSecondLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::vector< std::vector< iDynTree::SolidShape * > >::size_type result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("LinksSolidShapesVector_capacity",argc,1,1,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSecondLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_capacity" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSecondLinkIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->capacity(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSecondLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -61932,157 +65266,101 @@ int _wrap_LinksSolidShapesVector_capacity(int resc, mxArray *resv[], int argc, m } -int _wrap_delete_LinksSolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; +int _wrap_SixAxisForceTorqueSensor_setFirstLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_LinksSolidShapesVector",argc,1,1,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setFirstLinkName",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); - if (is_owned) { - delete arg1; + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - _out = (mxArray*)0; + result = (bool)(arg1)->setFirstLinkName((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ForwardPositionKinematics__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::Transform *arg3 = 0 ; - iDynTree::VectorDynSize *arg4 = 0 ; - iDynTree::LinkPositions *arg5 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_setSecondLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ForwardPositionKinematics",argc,5,5,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setSecondLinkName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); - } - arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPositionKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); - result = (bool)iDynTree::ForwardPositionKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::Transform const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5); + result = (bool)(arg1)->setSecondLinkName((std::string const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ForwardPositionKinematics__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::LinkPositions *arg4 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getFirstLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; - bool result; + std::string result; - if (!SWIG_check_num_args("ForwardPositionKinematics",argc,4,4,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getFirstLinkName",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getFirstLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); - result = (bool)iDynTree::ForwardPositionKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getFirstLinkName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -62090,258 +65368,127 @@ int _wrap_ForwardPositionKinematics__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_ForwardPositionKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ForwardPositionKinematics__SWIG_1(resc,resv,argc,argv); - } - } - } - } +int _wrap_SixAxisForceTorqueSensor_getSecondLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSecondLinkName",argc,1,1,0)) { + SWIG_fail; } - if (argc == 5) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ForwardPositionKinematics__SWIG_0(resc,resv,argc,argv); - } - } - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSecondLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ForwardPositionKinematics'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ForwardPositionKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::Transform const &,iDynTree::VectorDynSize const &,iDynTree::LinkPositions &)\n" - " iDynTree::ForwardPositionKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::LinkPositions &)\n"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSecondLinkName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ForwardVelAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::FreeFloatingAcc *arg5 = 0 ; - iDynTree::LinkVelArray *arg6 = 0 ; - iDynTree::LinkAccArray *arg7 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_setParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ForwardVelAccKinematics",argc,7,7,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setParentJoint",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); - result = (bool)iDynTree::ForwardVelAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,*arg6,*arg7); + result = (bool)(arg1)->setParentJoint((std::string const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ForwardPosVelAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::FreeFloatingAcc *arg5 = 0 ; - iDynTree::LinkPositions *arg6 = 0 ; - iDynTree::LinkVelArray *arg7 = 0 ; - iDynTree::LinkAccArray *arg8 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_setParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::JointIndex *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; - void *argp8 = 0 ; - int res8 = 0 ; + iDynTree::JointIndex temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ForwardPosVelAccKinematics",argc,8,8,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setParentJointIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPosVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPosVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPosVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPosVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPosVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardPosVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkPositions &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkPositions * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardPosVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkVelArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setParentJointIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg7 = reinterpret_cast< iDynTree::LinkVelArray * >(argp7); - res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res8)) { - SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "ForwardPosVelAccKinematics" "', argument " "8"" of type '" "iDynTree::LinkAccArray &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setParentJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + } + temp2 = static_cast< iDynTree::JointIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentJointIndex((iDynTree::JointIndex const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SixAxisForceTorqueSensor_setAppliedWrenchLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setAppliedWrenchLink",argc,2,2,0)) { + SWIG_fail; } - if (!argp8) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "8"" of type '" "iDynTree::LinkAccArray &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setAppliedWrenchLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg8 = reinterpret_cast< iDynTree::LinkAccArray * >(argp8); - result = (bool)iDynTree::ForwardPosVelAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,*arg6,*arg7,*arg8); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setAppliedWrenchLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (bool)(arg1)->setAppliedWrenchLink(arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -62350,81 +65497,23 @@ int _wrap_ForwardPosVelAccKinematics(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_ForwardPosVelKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::LinkPositions *arg5 = 0 ; - iDynTree::LinkVelArray *arg6 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; mxArray * _out; - bool result; + std::string result; - if (!SWIG_check_num_args("ForwardPosVelKinematics",argc,6,6,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getName",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPosVelKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPosVelKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPosVelKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPosVelKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPosVelKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardPosVelKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); - result = (bool)iDynTree::ForwardPosVelKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,*arg5,*arg6); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -62432,92 +65521,23 @@ int _wrap_ForwardPosVelKinematics(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_ForwardAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::FreeFloatingAcc *arg5 = 0 ; - iDynTree::LinkVelArray *arg6 = 0 ; - iDynTree::LinkAccArray *arg7 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; mxArray * _out; - bool result; + iDynTree::SensorType result; - if (!SWIG_check_num_args("ForwardAccKinematics",argc,7,7,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); - result = (bool)iDynTree::ForwardAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,(iDynTree::LinkVelArray const &)*arg6,*arg7); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -62525,92 +65545,47 @@ int _wrap_ForwardAccKinematics(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_ForwardBiasAccKinematics__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::SpatialAcc *arg5 = 0 ; - iDynTree::LinkVelArray *arg6 = 0 ; - iDynTree::LinkAccArray *arg7 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; mxArray * _out; - bool result; + std::string result; - if (!SWIG_check_num_args("ForwardBiasAccKinematics",argc,7,7,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getParentJoint",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::SpatialAcc const &""'"); - } - arg5 = reinterpret_cast< iDynTree::SpatialAcc * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getParentJoint" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardBiasAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getParentJoint(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SixAxisForceTorqueSensor_getParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::JointIndex result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getParentJointIndex",argc,1,1,0)) { + SWIG_fail; } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getParentJointIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); - result = (bool)iDynTree::ForwardBiasAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::SpatialAcc const &)*arg5,(iDynTree::LinkVelArray const &)*arg6,*arg7); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getParentJointIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -62618,80 +65593,22 @@ int _wrap_ForwardBiasAccKinematics__SWIG_0(int resc, mxArray *resv[], int argc, } -int _wrap_ForwardBiasAccKinematics__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::LinkVelArray *arg5 = 0 ; - iDynTree::LinkAccArray *arg6 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ForwardBiasAccKinematics",argc,6,6,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_isValid",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkVelArray * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_isValid" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); - result = (bool)iDynTree::ForwardBiasAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::LinkVelArray const &)*arg5,*arg6); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->isValid(); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -62700,141 +65617,57 @@ int _wrap_ForwardBiasAccKinematics__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_ForwardBiasAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 6) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ForwardBiasAccKinematics__SWIG_1(resc,resv,argc,argv); - } - } - } - } - } - } +int _wrap_SixAxisForceTorqueSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Sensor *result = 0 ; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_clone",argc,1,1,0)) { + SWIG_fail; } - if (argc == 7) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[6], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ForwardBiasAccKinematics__SWIG_0(resc,resv,argc,argv); - } - } - } - } - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_clone" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ForwardBiasAccKinematics'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ForwardBiasAccKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::SpatialAcc const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray &)\n" - " iDynTree::ForwardBiasAccKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray &)\n"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_ComputeLinearAndAngularMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::LinkPositions *arg2 = 0 ; - iDynTree::LinkVelArray *arg3 = 0 ; - iDynTree::SpatialMomentum *arg4 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ComputeLinearAndAngularMomentum",argc,4,4,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); - } - arg2 = reinterpret_cast< iDynTree::LinkPositions * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg3 = reinterpret_cast< iDynTree::LinkVelArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "4"" of type '" "iDynTree::SpatialMomentum &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "4"" of type '" "iDynTree::SpatialMomentum &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg4 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp4); - result = (bool)iDynTree::ComputeLinearAndAngularMomentum((iDynTree::Model const &)*arg1,(iDynTree::LinkPositions const &)*arg2,(iDynTree::LinkVelArray const &)*arg3,*arg4); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -62843,69 +65676,54 @@ int _wrap_ComputeLinearAndAngularMomentum(int resc, mxArray *resv[], int argc, m } -int _wrap_ComputeLinearAndAngularMomentumDerivativeBias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::LinkPositions *arg2 = 0 ; - iDynTree::LinkVelArray *arg3 = 0 ; - iDynTree::LinkAccArray *arg4 = 0 ; - iDynTree::Wrench *arg5 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getAppliedWrenchLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; mxArray * _out; - bool result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("ComputeLinearAndAngularMomentumDerivativeBias",argc,5,5,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getAppliedWrenchLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); - } - arg2 = reinterpret_cast< iDynTree::LinkPositions * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg3 = reinterpret_cast< iDynTree::LinkVelArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getAppliedWrenchLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg4 = reinterpret_cast< iDynTree::LinkAccArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "5"" of type '" "iDynTree::Wrench &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getAppliedWrenchLink(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_SixAxisForceTorqueSensor_isLinkAttachedToSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + void *argp1 = 0 ; + int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_isLinkAttachedToSensor",argc,2,2,0)) { + SWIG_fail; } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "5"" of type '" "iDynTree::Wrench &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_isLinkAttachedToSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg5 = reinterpret_cast< iDynTree::Wrench * >(argp5); - result = (bool)iDynTree::ComputeLinearAndAngularMomentumDerivativeBias((iDynTree::Model const &)*arg1,(iDynTree::LinkPositions const &)*arg2,(iDynTree::LinkVelArray const &)*arg3,(iDynTree::LinkAccArray const &)*arg4,*arg5); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_isLinkAttachedToSensor" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->isLinkAttachedToSensor(arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -62914,102 +65732,41 @@ int _wrap_ComputeLinearAndAngularMomentumDerivativeBias(int resc, mxArray *resv[ } -int _wrap_RNEADynamicPhase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::JointPosDoubleArray *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::LinkAccArray *arg5 = 0 ; - iDynTree::LinkNetExternalWrenches *arg6 = 0 ; - iDynTree::LinkInternalWrenches *arg7 = 0 ; - iDynTree::FreeFloatingGeneralizedTorques *arg8 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Transform *arg3 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; - void *argp8 = 0 ; - int res8 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("RNEADynamicPhase",argc,8,8,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getLinkSensorTransform",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RNEADynamicPhase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RNEADynamicPhase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "RNEADynamicPhase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); - } - arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "RNEADynamicPhase" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "RNEADynamicPhase" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "RNEADynamicPhase" "', argument " "6"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "6"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "RNEADynamicPhase" "', argument " "7"" of type '" "iDynTree::LinkInternalWrenches &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "7"" of type '" "iDynTree::LinkInternalWrenches &""'"); - } - arg7 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp7); - res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 ); - if (!SWIG_IsOK(res8)) { - SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "RNEADynamicPhase" "', argument " "8"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); - } - if (!argp8) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "8"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform &""'"); } - arg8 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp8); - result = (bool)iDynTree::RNEADynamicPhase((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,(iDynTree::LinkWrenches const &)*arg6,*arg7,*arg8); + arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getLinkSensorTransform(arg2,*arg3); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -63018,69 +65775,52 @@ int _wrap_RNEADynamicPhase(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_CompositeRigidBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::JointPosDoubleArray *arg3 = 0 ; - iDynTree::LinkCompositeRigidBodyInertias *arg4 = 0 ; - iDynTree::FreeFloatingMassMatrix *arg5 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Wrench *arg3 = 0 ; + iDynTree::Wrench *arg4 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; void *argp3 ; int res3 = 0 ; void *argp4 = 0 ; int res4 = 0 ; - void *argp5 = 0 ; - int res5 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("CompositeRigidBodyAlgorithm",argc,5,5,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLink",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Wrench, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); } - arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkInertias, 0 ); + arg3 = reinterpret_cast< iDynTree::Wrench * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::LinkCompositeRigidBodyInertias &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::LinkCompositeRigidBodyInertias &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkCompositeRigidBodyInertias * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::FreeFloatingMassMatrix &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::FreeFloatingMassMatrix &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); } - arg5 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp5); - result = (bool)iDynTree::CompositeRigidBodyAlgorithm((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4,*arg5); + arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLink(arg2,(iDynTree::Wrench const &)*arg3,*arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -63089,43 +65829,42 @@ int _wrap_CompositeRigidBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *result = 0 ; - - if (!SWIG_check_num_args("new_ArticulatedBodyAlgorithmInternalBuffers",argc,0,0,0)) { - SWIG_fail; - } - (void)argv; - result = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *)new iDynTree::ArticulatedBodyAlgorithmInternalBuffers(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - void *argp1 ; +int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Matrix6x6 *arg3 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_ArticulatedBodyAlgorithmInternalBuffers",argc,1,1,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - result = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *)new iDynTree::ArticulatedBodyAlgorithmInternalBuffers((iDynTree::Model const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 1 | 0 ); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); + } + arg3 = reinterpret_cast< iDynTree::Matrix6x6 * >(argp3); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLinkMatrix(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63133,55 +65872,42 @@ int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_1(int resc, mxArray } -int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ArticulatedBodyAlgorithmInternalBuffers'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ArticulatedBodyAlgorithmInternalBuffers::ArticulatedBodyAlgorithmInternalBuffers()\n" - " iDynTree::ArticulatedBodyAlgorithmInternalBuffers::ArticulatedBodyAlgorithmInternalBuffers(iDynTree::Model const &)\n"); - return 1; -} - - -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::LinkIndex arg2 ; + iDynTree::Matrix6x6 *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + arg2 = static_cast< iDynTree::LinkIndex >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - (arg1)->resize((iDynTree::Model const &)*arg2); - _out = (mxArray*)0; + arg3 = reinterpret_cast< iDynTree::Matrix6x6 * >(argp3); + result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLinkInverseMatrix(arg2,*arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63189,34 +65915,45 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_resize(int resc, mxArray *resv } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SixAxisForceTorqueSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::LinkInternalWrenches *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - bool result; + iDynTree::Wrench result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_predictMeasurement",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + } + arg3 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp3); + result = (arg1)->predictMeasurement((iDynTree::Traversal const &)*arg2,(iDynTree::LinkInternalWrenches const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63224,30 +65961,34 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_isConsistent(int resc, mxArray } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::DOFSpatialMotionArray *arg2 = (iDynTree::DOFSpatialMotionArray *) 0 ; +int _wrap_SixAxisForceTorqueSensor_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + std::string result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_S_set",argc,2,2,0)) { + if (!SWIG_check_num_args("SixAxisForceTorqueSensor_toString",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_set" "', argument " "2"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg2 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp2); - if (arg1) (arg1)->S = *arg2; - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->toString((iDynTree::Model const &)*arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63255,23 +65996,16 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_set(int resc, mxArray *resv[ } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_AccelerometerSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::DOFSpatialMotionArray *result = 0 ; + iDynTree::AccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_S_get",argc,1,1,0)) { + if (!SWIG_check_num_args("new_AccelerometerSensor",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::DOFSpatialMotionArray *)& ((arg1)->S); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); + (void)argv; + result = (iDynTree::AccelerometerSensor *)new iDynTree::AccelerometerSensor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63279,30 +66013,26 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_get(int resc, mxArray *resv[ } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_U_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::DOFSpatialForceArray *arg2 = (iDynTree::DOFSpatialForceArray *) 0 ; - void *argp1 = 0 ; +int _wrap_new_AccelerometerSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + iDynTree::AccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_U_set",argc,2,2,0)) { + if (!SWIG_check_num_args("new_AccelerometerSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const &""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_set" "', argument " "2"" of type '" "iDynTree::DOFSpatialForceArray *""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const &""'"); } - arg2 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp2); - if (arg1) (arg1)->U = *arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = (iDynTree::AccelerometerSensor *)new iDynTree::AccelerometerSensor((iDynTree::AccelerometerSensor const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63310,53 +66040,47 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_U_set(int resc, mxArray *resv[ } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_U_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::DOFSpatialForceArray *result = 0 ; - - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_U_get",argc,1,1,0)) { - SWIG_fail; +int _wrap_new_AccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_AccelerometerSensor__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__AccelerometerSensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_AccelerometerSensor__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::DOFSpatialForceArray *)& ((arg1)->U); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_AccelerometerSensor'." + " Possible C/C++ prototypes are:\n" + " iDynTree::AccelerometerSensor::AccelerometerSensor()\n" + " iDynTree::AccelerometerSensor::AccelerometerSensor(iDynTree::AccelerometerSensor const &)\n"); return 1; } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_D_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::JointDOFsDoubleArray *arg2 = (iDynTree::JointDOFsDoubleArray *) 0 ; +int _wrap_delete_AccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_D_set",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_AccelerometerSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_set" "', argument " "2"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp2); - if (arg1) (arg1)->D = *arg2; _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -63365,54 +66089,73 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_D_set(int resc, mxArray *resv[ } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_D_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_D_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_setName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setName" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *)& ((arg1)->D); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setName((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_u_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::JointDOFsDoubleArray *arg2 = (iDynTree::JointDOFsDoubleArray *) 0 ; +int _wrap_AccelerometerSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_u_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_setLinkSensorTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_set" "', argument " "2"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg2 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp2); - if (arg1) (arg1)->u = *arg2; - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63420,54 +66163,72 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_u_set(int resc, mxArray *resv[ } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_u_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::JointDOFsDoubleArray *result = 0 ; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_u_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_setParentLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::JointDOFsDoubleArray *)& ((arg1)->u); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setParentLink((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::LinkVelArray *arg2 = (iDynTree::LinkVelArray *) 0 ; +int _wrap_AccelerometerSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + iDynTree::LinkIndex temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksVel_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_setParentLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set" "', argument " "2"" of type '" "iDynTree::LinkVelArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg2 = reinterpret_cast< iDynTree::LinkVelArray * >(argp2); - if (arg1) (arg1)->linksVel = *arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "AccelerometerSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63475,23 +66236,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_set(int resc, mxArray } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkVelArray *result = 0 ; + std::string result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksVel_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_getName",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getName" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::LinkVelArray *)& ((arg1)->linksVel); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = ((iDynTree::AccelerometerSensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63499,30 +66260,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_get(int resc, mxArray } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::LinkAccArray *arg2 = (iDynTree::LinkAccArray *) 0 ; +int _wrap_AccelerometerSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + iDynTree::SensorType result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set" "', argument " "2"" of type '" "iDynTree::LinkAccArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::LinkAccArray * >(argp2); - if (arg1) (arg1)->linksBiasAcceleration = *arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::AccelerometerSensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63530,23 +66284,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set(int } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkAccArray *result = 0 ; + std::string result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_getParentLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::LinkAccArray *)& ((arg1)->linksBiasAcceleration); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = ((iDynTree::AccelerometerSensor const *)arg1)->getParentLink(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63554,30 +66308,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get(int } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::LinkAccArray *arg2 = (iDynTree::LinkAccArray *) 0 ; +int _wrap_AccelerometerSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_getParentLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set" "', argument " "2"" of type '" "iDynTree::LinkAccArray *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::LinkAccArray * >(argp2); - if (arg1) (arg1)->linksAccelerations = *arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = ((iDynTree::AccelerometerSensor const *)arg1)->getParentLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63585,23 +66332,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set(int res } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkAccArray *result = 0 ; + iDynTree::Transform result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_getLinkSensorTransform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::LinkAccArray *)& ((arg1)->linksAccelerations); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = ((iDynTree::AccelerometerSensor const *)arg1)->getLinkSensorTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63609,30 +66356,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get(int res } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::LinkArticulatedBodyInertias *arg2 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; +int _wrap_AccelerometerSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_isValid",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set" "', argument " "2"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_isValid" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp2); - if (arg1) (arg1)->linkABIs = *arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = (bool)((iDynTree::AccelerometerSensor const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63640,23 +66380,23 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set(int resc, mxArray } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkArticulatedBodyInertias *result = 0 ; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_clone",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_clone" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::LinkArticulatedBodyInertias *)& ((arg1)->linkABIs); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::AccelerometerSensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63664,30 +66404,34 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get(int resc, mxArray } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - iDynTree::LinkWrenches *arg2 = (iDynTree::LinkWrenches *) 0 ; +int _wrap_AccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set",argc,2,2,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set" "', argument " "2"" of type '" "iDynTree::LinkWrenches *""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg2 = reinterpret_cast< iDynTree::LinkWrenches * >(argp2); - if (arg1) (arg1)->linksBiasWrench = *arg2; - _out = (mxArray*)0; + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63695,23 +66439,45 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set(int resc, } -int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; +int _wrap_AccelerometerSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; + iDynTree::Twist *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; - iDynTree::LinkWrenches *result = 0 ; + iDynTree::LinAcceleration result; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get",argc,1,1,0)) { + if (!SWIG_check_num_args("AccelerometerSensor_predictMeasurement",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - result = (iDynTree::LinkWrenches *)& ((arg1)->linksBiasWrench); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); + result = (arg1)->predictMeasurement((iDynTree::SpatialAcc const &)*arg2,(iDynTree::Twist const &)*arg3); + _out = SWIG_NewPointerObj((new iDynTree::LinAcceleration(static_cast< const iDynTree::LinAcceleration& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63719,26 +66485,16 @@ int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get(int resc, } -int _wrap_delete_ArticulatedBodyAlgorithmInternalBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_GyroscopeSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; + iDynTree::GyroscopeSensor *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_ArticulatedBodyAlgorithmInternalBuffers",argc,1,1,0)) { + if (!SWIG_check_num_args("new_GyroscopeSensor",argc,0,0,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); - } - arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); - if (is_owned) { - delete arg1; - } - _out = (mxArray*)0; + (void)argv; + result = (iDynTree::GyroscopeSensor *)new iDynTree::GyroscopeSensor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63746,103 +66502,75 @@ int _wrap_delete_ArticulatedBodyAlgorithmInternalBuffers(int resc, mxArray *resv } -int _wrap_ArticulatedBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::FreeFloatingPos *arg3 = 0 ; - iDynTree::FreeFloatingVel *arg4 = 0 ; - iDynTree::LinkNetExternalWrenches *arg5 = 0 ; - iDynTree::JointDOFsDoubleArray *arg6 = 0 ; - iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg7 = 0 ; - iDynTree::FreeFloatingAcc *arg8 = 0 ; +int _wrap_new_GyroscopeSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = 0 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; - void *argp8 = 0 ; - int res8 = 0 ; mxArray * _out; - bool result; + iDynTree::GyroscopeSensor *result = 0 ; - if (!SWIG_check_num_args("ArticulatedBodyAlgorithm",argc,8,8,0)) { + if (!SWIG_check_num_args("new_GyroscopeSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ArticulatedBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ArticulatedBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ArticulatedBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ArticulatedBodyAlgorithm" "', argument " "6"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const &""'"); } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "6"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = (iDynTree::GyroscopeSensor *)new iDynTree::GyroscopeSensor((iDynTree::GyroscopeSensor const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_GyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_GyroscopeSensor__SWIG_0(resc,resv,argc,argv); } - arg6 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ArticulatedBodyAlgorithm" "', argument " "7"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers &""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GyroscopeSensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_GyroscopeSensor__SWIG_1(resc,resv,argc,argv); + } } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "7"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers &""'"); + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_GyroscopeSensor'." + " Possible C/C++ prototypes are:\n" + " iDynTree::GyroscopeSensor::GyroscopeSensor()\n" + " iDynTree::GyroscopeSensor::GyroscopeSensor(iDynTree::GyroscopeSensor const &)\n"); + return 1; +} + + +int _wrap_delete_GyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + + int is_owned; + if (!SWIG_check_num_args("delete_GyroscopeSensor",argc,1,1,0)) { + SWIG_fail; } - arg7 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp7); - res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res8)) { - SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "ArticulatedBodyAlgorithm" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - if (!argp8) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + if (is_owned) { + delete arg1; } - arg8 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp8); - result = (bool)iDynTree::ArticulatedBodyAlgorithm((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::LinkWrenches const &)*arg5,(iDynTree::JointDOFsDoubleArray const &)*arg6,*arg7,*arg8); - _out = SWIG_From_bool(static_cast< bool >(result)); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63850,112 +66578,73 @@ int _wrap_ArticulatedBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_InverseDynamicsInertialParametersRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::Traversal *arg2 = 0 ; - iDynTree::LinkPositions *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::LinkAccArray *arg5 = 0 ; - iDynTree::MatrixDynSize *arg6 = 0 ; - void *argp1 ; +int _wrap_GyroscopeSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 = 0 ; - int res6 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; bool result; - if (!SWIG_check_num_args("InverseDynamicsInertialParametersRegressor",argc,6,6,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_setName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "3"" of type '" "iDynTree::LinkPositions const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "3"" of type '" "iDynTree::LinkPositions const &""'"); - } - arg3 = reinterpret_cast< iDynTree::LinkPositions * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "6"" of type '" "iDynTree::MatrixDynSize &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setName" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "6"" of type '" "iDynTree::MatrixDynSize &""'"); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; } - arg6 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp6); - result = (bool)iDynTree::InverseDynamicsInertialParametersRegressor((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::LinkPositions const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,*arg6); + result = (bool)(arg1)->setName((std::string const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DHLink_A_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHLink_A_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_setLinkSensorTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_A_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_A_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->A = arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -63963,54 +66652,72 @@ int _wrap_DHLink_A_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_A_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - double result; + bool result; - if (!SWIG_check_num_args("DHLink_A_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_setParentLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_A_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->A); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setParentLink((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DHLink_D_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; + iDynTree::LinkIndex temp2 ; + ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHLink_D_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_setParentLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_D_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_D_set" "', argument " "2"" of type '" "double""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "GyroscopeSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->D = arg2; - _out = (mxArray*)0; + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64018,23 +66725,23 @@ int _wrap_DHLink_D_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_D_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double result; + std::string result; - if (!SWIG_check_num_args("DHLink_D_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_getName",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_D_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getName" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->D); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = ((iDynTree::GyroscopeSensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64042,30 +66749,23 @@ int _wrap_DHLink_D_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_Alpha_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; + iDynTree::SensorType result; - if (!SWIG_check_num_args("DHLink_Alpha_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Alpha_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Alpha_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->Alpha = arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::GyroscopeSensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64073,23 +66773,23 @@ int _wrap_DHLink_Alpha_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DHLink_Alpha_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double result; + std::string result; - if (!SWIG_check_num_args("DHLink_Alpha_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_getParentLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Alpha_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->Alpha); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = ((iDynTree::GyroscopeSensor const *)arg1)->getParentLink(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64097,30 +66797,23 @@ int _wrap_DHLink_Alpha_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DHLink_Offset_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("DHLink_Offset_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_getParentLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Offset_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Offset_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->Offset = arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = ((iDynTree::GyroscopeSensor const *)arg1)->getParentLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64128,23 +66821,23 @@ int _wrap_DHLink_Offset_set(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DHLink_Offset_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double result; + iDynTree::Transform result; - if (!SWIG_check_num_args("DHLink_Offset_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_getLinkSensorTransform",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Offset_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->Offset); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = ((iDynTree::GyroscopeSensor const *)arg1)->getLinkSensorTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64152,30 +66845,23 @@ int _wrap_DHLink_Offset_get(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_DHLink_Min_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHLink_Min_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_isValid",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Min_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_isValid" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Min_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->Min = arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = (bool)((iDynTree::GyroscopeSensor const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64183,23 +66869,23 @@ int _wrap_DHLink_Min_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_Min_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - double result; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("DHLink_Min_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_clone",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Min_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_clone" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->Min); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::GyroscopeSensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64207,30 +66893,34 @@ int _wrap_DHLink_Min_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_Max_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - double arg2 ; +int _wrap_GyroscopeSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - double val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHLink_Max_set",argc,2,2,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Max_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Max_set" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - if (arg1) (arg1)->Max = arg2; - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64238,23 +66928,34 @@ int _wrap_DHLink_Max_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHLink_Max_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; +int _wrap_GyroscopeSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; + iDynTree::Twist *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - double result; + iDynTree::AngVelocity result; - if (!SWIG_check_num_args("DHLink_Max_get",argc,1,1,0)) { + if (!SWIG_check_num_args("GyroscopeSensor_predictMeasurement",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Max_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - result = (double) ((arg1)->Max); - _out = SWIG_From_double(static_cast< double >(result)); + arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); + result = (arg1)->predictMeasurement((iDynTree::Twist const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::AngVelocity(static_cast< const iDynTree::AngVelocity& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64262,16 +66963,16 @@ int _wrap_DHLink_Max_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_new_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::DHLink *result = 0 ; + iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("new_DHLink",argc,0,0,0)) { + if (!SWIG_check_num_args("new_ThreeAxisAngularAccelerometerSensor",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::DHLink *)new iDynTree::DHLink(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 1 | 0 ); + result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)new iDynTree::ThreeAxisAngularAccelerometerSensor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64279,26 +66980,26 @@ int _wrap_new_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; - void *argp1 = 0 ; +int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; + iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_DHLink",argc,1,1,0)) { + if (!SWIG_check_num_args("new_ThreeAxisAngularAccelerometerSensor",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DHLink" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const &""'"); } - arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)new iDynTree::ThreeAxisAngularAccelerometerSensor((iDynTree::ThreeAxisAngularAccelerometerSensor const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64306,29 +67007,47 @@ int _wrap_delete_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHChain_setNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - size_t arg2 ; +int _wrap_new_ThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ThreeAxisAngularAccelerometerSensor'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ThreeAxisAngularAccelerometerSensor::ThreeAxisAngularAccelerometerSensor()\n" + " iDynTree::ThreeAxisAngularAccelerometerSensor::ThreeAxisAngularAccelerometerSensor(iDynTree::ThreeAxisAngularAccelerometerSensor const &)\n"); + return 1; +} + + +int _wrap_delete_ThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("DHChain_setNrOfDOFs",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_ThreeAxisAngularAccelerometerSensor",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setNrOfDOFs" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_setNrOfDOFs" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - (arg1)->setNrOfDOFs(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -64337,57 +67056,73 @@ int _wrap_DHChain_setNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_DHChain_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - size_t result; + bool result; - if (!SWIG_check_num_args("DHChain_getNrOfDOFs",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - result = ((iDynTree::DHChain const *)arg1)->getNrOfDOFs(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setName((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DHChain_setH0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHChain_setH0",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setH0" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_setH0" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setH0" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - (arg1)->setH0((iDynTree::Transform const &)*arg2); - _out = (mxArray*)0; + result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64395,57 +67130,96 @@ int _wrap_DHChain_setH0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHChain_getH0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + std::string *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::Transform *result = 0 ; + bool result; - if (!SWIG_check_num_args("DHChain_getH0",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setParentLink",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getH0" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - result = (iDynTree::Transform *) &((iDynTree::DHChain const *)arg1)->getH0(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + result = (bool)(arg1)->setParentLink((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_DHChain_setHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + iDynTree::LinkIndex temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; + bool result; - if (!SWIG_check_num_args("DHChain_setHN",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setParentLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setHN" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_setHN" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_ThreeAxisAngularAccelerometerSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getName",argc,1,1,0)) { + SWIG_fail; } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setHN" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getName" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - (arg1)->setHN((iDynTree::Transform const &)*arg2); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64453,23 +67227,23 @@ int _wrap_DHChain_setHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHChain_getHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform *result = 0 ; + iDynTree::SensorType result; - if (!SWIG_check_num_args("DHChain_getHN",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getHN" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - result = (iDynTree::Transform *) &((iDynTree::DHChain const *)arg1)->getHN(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64477,31 +67251,23 @@ int _wrap_DHChain_getHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_DHChain_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - size_t arg2 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::DHLink *result = 0 ; + std::string result; - if (!SWIG_check_num_args("DHChain_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getParentLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_paren" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_paren" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::DHLink *) &(arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getParentLink(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64509,31 +67275,23 @@ int _wrap_DHChain_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_DHChain_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - size_t arg2 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::DHLink *result = 0 ; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("DHChain_paren",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getParentLinkIndex",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_paren" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_paren" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = (iDynTree::DHLink *) &((iDynTree::DHChain const *)arg1)->operator ()(arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getParentLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64541,71 +67299,47 @@ int _wrap_DHChain_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_DHChain_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_DHChain_paren__SWIG_0(resc,resv,argc,argv); - } - } +int _wrap_ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + iDynTree::Transform result; + + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform",argc,1,1,0)) { + SWIG_fail; } - if (argc == 2) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_size_t(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_DHChain_paren__SWIG_1(resc,resv,argc,argv); - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DHChain_paren'." - " Possible C/C++ prototypes are:\n" - " iDynTree::DHChain::operator ()(size_t const)\n" - " iDynTree::DHChain::operator ()(size_t const) const\n"); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getLinkSensorTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_DHChain_getDOFName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - size_t arg2 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("DHChain_getDOFName",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_isValid",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getDOFName" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_isValid" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_getDOFName" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - result = ((iDynTree::DHChain const *)arg1)->getDOFName(arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = (bool)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64613,79 +67347,57 @@ int _wrap_DHChain_getDOFName(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_DHChain_setDOFName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - size_t arg2 ; - std::string *arg3 = 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - size_t val2 ; - int ecode2 = 0 ; - int res3 = SWIG_OLDOBJ ; mxArray * _out; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("DHChain_setDOFName",argc,3,3,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_clone",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setDOFName" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); - } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - ecode2 = SWIG_AsVal_size_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_setDOFName" "', argument " "2"" of type '" "size_t""'"); - } - arg2 = static_cast< size_t >(val2); - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "DHChain_setDOFName" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setDOFName" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_clone" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); } - (arg1)->setDOFName(arg2,(std::string const &)*arg3); - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_DHChain_toModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; + void *argp2 ; int res2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("DHChain_toModel",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_toModel" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_toModel" "', argument " "2"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_toModel" "', argument " "2"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::DHChain const *)arg1)->toModel(*arg2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -64694,54 +67406,34 @@ int _wrap_DHChain_toModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_DHChain_fromModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - iDynTree::Model *arg2 = 0 ; - std::string arg3 ; - std::string arg4 ; +int _wrap_ThreeAxisAngularAccelerometerSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; + iDynTree::SpatialAcc *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Vector3 result; - if (!SWIG_check_num_args("DHChain_fromModel",argc,4,4,0)) { + if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_predictMeasurement",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_fromModel" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_fromModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_fromModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "DHChain_fromModel" "', argument " "3"" of type '" "std::string""'"); - } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[3], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "DHChain_fromModel" "', argument " "4"" of type '" "std::string""'"); - } - arg4 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); } - result = (bool)(arg1)->fromModel((iDynTree::Model const &)*arg2,arg3,arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); + result = (arg1)->predictMeasurement((iDynTree::SpatialAcc const &)*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64749,16 +67441,16 @@ int _wrap_DHChain_fromModel(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_new_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::DHChain *result = 0 ; + iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; - if (!SWIG_check_num_args("new_DHChain",argc,0,0,0)) { + if (!SWIG_check_num_args("new_ThreeAxisForceTorqueContactSensor",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::DHChain *)new iDynTree::DHChain(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHChain, 1 | 0 ); + result = (iDynTree::ThreeAxisForceTorqueContactSensor *)new iDynTree::ThreeAxisForceTorqueContactSensor(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64766,26 +67458,26 @@ int _wrap_new_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_delete_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; - void *argp1 = 0 ; +int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; + iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_DHChain",argc,1,1,0)) { + if (!SWIG_check_num_args("new_ThreeAxisForceTorqueContactSensor",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DHChain" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const &""'"); } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = (iDynTree::ThreeAxisForceTorqueContactSensor *)new iDynTree::ThreeAxisForceTorqueContactSensor((iDynTree::ThreeAxisForceTorqueContactSensor const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64793,95 +67485,48 @@ int _wrap_delete_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_TransformFromDHCraig1989(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double arg4 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; - mxArray * _out; - iDynTree::Transform result; - - if (!SWIG_check_num_args("TransformFromDHCraig1989",argc,4,4,0)) { - SWIG_fail; +int _wrap_new_ThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_0(resc,resv,argc,argv); } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "TransformFromDHCraig1989" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "TransformFromDHCraig1989" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "TransformFromDHCraig1989" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "TransformFromDHCraig1989" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = iDynTree::TransformFromDHCraig1989(arg1,arg2,arg3,arg4); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_1(resc,resv,argc,argv); + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ThreeAxisForceTorqueContactSensor'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ThreeAxisForceTorqueContactSensor::ThreeAxisForceTorqueContactSensor()\n" + " iDynTree::ThreeAxisForceTorqueContactSensor::ThreeAxisForceTorqueContactSensor(iDynTree::ThreeAxisForceTorqueContactSensor const &)\n"); return 1; } -int _wrap_TransformFromDH(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - double arg1 ; - double arg2 ; - double arg3 ; - double arg4 ; - double val1 ; - int ecode1 = 0 ; - double val2 ; - int ecode2 = 0 ; - double val3 ; - int ecode3 = 0 ; - double val4 ; - int ecode4 = 0 ; +int _wrap_delete_ThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::Transform result; - if (!SWIG_check_num_args("TransformFromDH",argc,4,4,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_ThreeAxisForceTorqueContactSensor",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_double(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "TransformFromDH" "', argument " "1"" of type '" "double""'"); - } - arg1 = static_cast< double >(val1); - ecode2 = SWIG_AsVal_double(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "TransformFromDH" "', argument " "2"" of type '" "double""'"); - } - arg2 = static_cast< double >(val2); - ecode3 = SWIG_AsVal_double(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "TransformFromDH" "', argument " "3"" of type '" "double""'"); - } - arg3 = static_cast< double >(val3); - ecode4 = SWIG_AsVal_double(argv[3], &val4); - if (!SWIG_IsOK(ecode4)) { - SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "TransformFromDH" "', argument " "4"" of type '" "double""'"); - } - arg4 = static_cast< double >(val4); - result = iDynTree::TransformFromDH(arg1,arg2,arg3,arg4); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, SWIG_POINTER_DISOWN | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -64889,122 +67534,72 @@ int _wrap_TransformFromDH(int resc, mxArray *resv[], int argc, mxArray *argv[]) } -int _wrap_ExtractDHChainFromModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::string arg2 ; - std::string arg3 ; - iDynTree::DHChain *arg4 = 0 ; - double arg5 ; - void *argp1 ; +int _wrap_ThreeAxisForceTorqueContactSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; - double val5 ; - int ecode5 = 0 ; + int res2 = SWIG_OLDOBJ ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ExtractDHChainFromModel",argc,5,5,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); { std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "2"" of type '" "std::string const""'"); + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "3"" of type '" "std::string const""'"); + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__DHChain, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); + arg2 = ptr; } - arg4 = reinterpret_cast< iDynTree::DHChain * >(argp4); - ecode5 = SWIG_AsVal_double(argv[4], &val5); - if (!SWIG_IsOK(ecode5)) { - SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "ExtractDHChainFromModel" "', argument " "5"" of type '" "double""'"); - } - arg5 = static_cast< double >(val5); - result = (bool)iDynTree::ExtractDHChainFromModel((iDynTree::Model const &)*arg1,arg2,arg3,*arg4,arg5); + result = (bool)(arg1)->setName((std::string const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ExtractDHChainFromModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - std::string arg2 ; - std::string arg3 ; - iDynTree::DHChain *arg4 = 0 ; - void *argp1 ; +int _wrap_ThreeAxisForceTorqueContactSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + iDynTree::Transform *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ExtractDHChainFromModel",argc,4,4,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setLinkSensorTransform",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); - } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "2"" of type '" "std::string const""'"); - } - arg2 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; - } - { - std::string *ptr = (std::string *)0; - int res = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res) || !ptr) { - SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "3"" of type '" "std::string const""'"); - } - arg3 = *ptr; - if (SWIG_IsNewObj(res)) delete ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); } - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__DHChain, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - arg4 = reinterpret_cast< iDynTree::DHChain * >(argp4); - result = (bool)iDynTree::ExtractDHChainFromModel((iDynTree::Model const &)*arg1,arg2,arg3,*arg4); + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -65013,96 +67608,71 @@ int _wrap_ExtractDHChainFromModel__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_ExtractDHChainFromModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_ExtractDHChainFromModel__SWIG_1(resc,resv,argc,argv); - } - } - } - } +int _wrap_ThreeAxisForceTorqueContactSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + std::string *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setParentLink",argc,2,2,0)) { + SWIG_fail; } - if (argc == 5) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_double(argv[4], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_ExtractDHChainFromModel__SWIG_0(resc,resv,argc,argv); - } - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); } + arg2 = ptr; } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ExtractDHChainFromModel'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ExtractDHChainFromModel(iDynTree::Model const &,std::string const,std::string const,iDynTree::DHChain &,double)\n" - " iDynTree::ExtractDHChainFromModel(iDynTree::Model const &,std::string const,std::string const,iDynTree::DHChain &)\n"); + result = (bool)(arg1)->setParentLink((std::string const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_CreateModelFromDHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::DHChain *arg1 = 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 ; +int _wrap_ThreeAxisForceTorqueContactSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + iDynTree::LinkIndex *arg2 = 0 ; + void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + iDynTree::LinkIndex temp2 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("CreateModelFromDHChain",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setParentLinkIndex",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__DHChain, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "CreateModelFromDHChain" "', argument " "1"" of type '" "iDynTree::DHChain const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CreateModelFromDHChain" "', argument " "1"" of type '" "iDynTree::DHChain const &""'"); - } - arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "CreateModelFromDHChain" "', argument " "2"" of type '" "iDynTree::Model &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CreateModelFromDHChain" "', argument " "2"" of type '" "iDynTree::Model &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)iDynTree::CreateModelFromDHChain((iDynTree::DHChain const &)*arg1,*arg2); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + } + temp2 = static_cast< iDynTree::LinkIndex >(val2); + arg2 = &temp2; + result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -65111,29 +67681,47 @@ int _wrap_CreateModelFromDHChain(int resc, mxArray *resv[], int argc, mxArray *a } -SWIGINTERN int _wrap_NR_OF_SENSOR_TYPES_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - resv[0] = SWIG_From_int(static_cast< int >(iDynTree::NR_OF_SENSOR_TYPES)); +int _wrap_ThreeAxisForceTorqueContactSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::string result; + + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getName",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getName" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getName(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (_out) --resc, *resv++ = _out; return 0; +fail: + return 1; } -int _wrap_isLinkSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorType arg1 ; - int val1 ; - int ecode1 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::SensorType result; - if (!SWIG_check_num_args("isLinkSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getSensorType",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "isLinkSensor" "', argument " "1"" of type '" "iDynTree::SensorType""'"); - } - arg1 = static_cast< iDynTree::SensorType >(val1); - result = (bool)iDynTree::isLinkSensor(arg1); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = (iDynTree::SensorType)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getSensorType(); + _out = SWIG_From_int(static_cast< int >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65141,23 +67729,23 @@ int _wrap_isLinkSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_isJointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorType arg1 ; - int val1 ; - int ecode1 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - bool result; + std::string result; - if (!SWIG_check_num_args("isJointSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getParentLink",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "isJointSensor" "', argument " "1"" of type '" "iDynTree::SensorType""'"); - } - arg1 = static_cast< iDynTree::SensorType >(val1); - result = (bool)iDynTree::isJointSensor(arg1); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getParentLink(); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65165,23 +67753,23 @@ int _wrap_isJointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_getSensorTypeSize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorType arg1 ; - int val1 ; - int ecode1 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - std::size_t result; + iDynTree::LinkIndex result; - if (!SWIG_check_num_args("getSensorTypeSize",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getParentLinkIndex",argc,1,1,0)) { SWIG_fail; } - ecode1 = SWIG_AsVal_int(argv[0], &val1); - if (!SWIG_IsOK(ecode1)) { - SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "getSensorTypeSize" "', argument " "1"" of type '" "iDynTree::SensorType""'"); - } - arg1 = static_cast< iDynTree::SensorType >(val1); - result = iDynTree::getSensorTypeSize(arg1); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getParentLinkIndex(); + _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65189,26 +67777,23 @@ int _wrap_getSensorTypeSize(int resc, mxArray *resv[], int argc, mxArray *argv[] } -int _wrap_delete_Sensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::Transform result; - int is_owned; - if (!SWIG_check_num_args("delete_Sensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getLinkSensorTransform",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_Sensor" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getLinkSensorTransform(); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65216,23 +67801,23 @@ int _wrap_delete_Sensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Sensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("Sensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_isValid",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_getName" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_isValid" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - result = ((iDynTree::Sensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = (bool)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->isValid(); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65240,23 +67825,23 @@ int _wrap_Sensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Sensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SensorType result; + iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("Sensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_clone",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_getSensorType" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_clone" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::Sensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = (iDynTree::Sensor *)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->clone(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65264,22 +67849,33 @@ int _wrap_Sensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_Sensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("Sensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_updateIndices",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_isValid" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - result = (bool)((iDynTree::Sensor const *)arg1)->isValid(); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -65288,62 +67884,57 @@ int _wrap_Sensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Sensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_setLoadCellLocations(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("Sensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setLoadCellLocations",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_setName" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; - } - result = (bool)(arg1)->setName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + } + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "2"" of type '" "std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "2"" of type '" "std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > &""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > * >(argp2); + (arg1)->setLoadCellLocations(*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_Sensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_getLoadCellLocations(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; + SwigValueWrapper< std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > > result; - if (!SWIG_check_num_args("Sensor_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getLoadCellLocations",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_clone" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getLoadCellLocations" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::Sensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getLoadCellLocations(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::Position,std::allocator< iDynTree::Position > >(static_cast< const std::vector< iDynTree::Position,std::allocator< iDynTree::Position > >& >(result))), SWIGTYPE_p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65351,34 +67942,34 @@ int _wrap_Sensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { } -int _wrap_Sensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Vector3 result; - if (!SWIG_check_num_args("Sensor_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_isConsistent" "', argument " "1"" of type '" "iDynTree::Sensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::Sensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->computeThreeAxisForceTorqueFromLoadCellMeasurements(*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65386,34 +67977,34 @@ int _wrap_Sensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv } -int _wrap_Sensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Sensor *arg1 = (iDynTree::Sensor *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::Position result; - if (!SWIG_check_num_args("Sensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "Sensor_updateIndices" "', argument " "1"" of type '" "iDynTree::Sensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); } - arg1 = reinterpret_cast< iDynTree::Sensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "Sensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "Sensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->computeCenterOfPressureFromLoadCellMeasurements(*arg2); + _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65421,26 +68012,169 @@ int _wrap_Sensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *arg } -int _wrap_delete_JointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_predictSensorsMeasurements__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::FreeFloatingAcc *arg5 = 0 ; + iDynTree::LinAcceleration *arg6 = 0 ; + iDynTree::LinkNetExternalWrenches *arg7 = 0 ; + iDynTree::FreeFloatingAcc *arg8 = 0 ; + iDynTree::LinkPositions *arg9 = 0 ; + iDynTree::LinkVelArray *arg10 = 0 ; + iDynTree::LinkAccArray *arg11 = 0 ; + iDynTree::LinkInternalWrenches *arg12 = 0 ; + iDynTree::FreeFloatingGeneralizedTorques *arg13 = 0 ; + iDynTree::SensorsMeasurements *arg14 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 ; + int res7 = 0 ; + void *argp8 = 0 ; + int res8 = 0 ; + void *argp9 = 0 ; + int res9 = 0 ; + void *argp10 = 0 ; + int res10 = 0 ; + void *argp11 = 0 ; + int res11 = 0 ; + void *argp12 = 0 ; + int res12 = 0 ; + void *argp13 = 0 ; + int res13 = 0 ; + void *argp14 = 0 ; + int res14 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_JointSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("predictSensorsMeasurements",argc,14,14,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_JointSensor" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::LinAcceleration const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::LinAcceleration const &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinAcceleration * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp7); + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + arg8 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp8); + res9 = SWIG_ConvertPtr(argv[8], &argp9, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res9)) { + SWIG_exception_fail(SWIG_ArgError(res9), "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp9) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::LinkPositions &""'"); + } + arg9 = reinterpret_cast< iDynTree::LinkPositions * >(argp9); + res10 = SWIG_ConvertPtr(argv[9], &argp10, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res10)) { + SWIG_exception_fail(SWIG_ArgError(res10), "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp10) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg10 = reinterpret_cast< iDynTree::LinkVelArray * >(argp10); + res11 = SWIG_ConvertPtr(argv[10], &argp11, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res11)) { + SWIG_exception_fail(SWIG_ArgError(res11), "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp11) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg11 = reinterpret_cast< iDynTree::LinkAccArray * >(argp11); + res12 = SWIG_ConvertPtr(argv[11], &argp12, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res12)) { + SWIG_exception_fail(SWIG_ArgError(res12), "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + if (!argp12) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + arg12 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp12); + res13 = SWIG_ConvertPtr(argv[12], &argp13, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 ); + if (!SWIG_IsOK(res13)) { + SWIG_exception_fail(SWIG_ArgError(res13), "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + } + if (!argp13) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + } + arg13 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp13); + res14 = SWIG_ConvertPtr(argv[13], &argp14, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); + if (!SWIG_IsOK(res14)) { + SWIG_exception_fail(SWIG_ArgError(res14), "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + if (!argp14) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + arg14 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp14); + result = (bool)iDynTree::predictSensorsMeasurements((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,(iDynTree::GeomVector3 const &)*arg6,(iDynTree::LinkWrenches const &)*arg7,*arg8,*arg9,*arg10,*arg11,*arg12,*arg13,*arg14); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65448,23 +68182,81 @@ int _wrap_delete_JointSensor(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_JointSensor_getParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_predictSensorsMeasurementsFromRawBuffers__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::LinkVelArray *arg3 = 0 ; + iDynTree::LinkAccArray *arg4 = 0 ; + iDynTree::LinkInternalWrenches *arg5 = 0 ; + iDynTree::SensorsMeasurements *arg6 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("JointSensor_getParentJoint",argc,1,1,0)) { + if (!SWIG_check_num_args("predictSensorsMeasurementsFromRawBuffers",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_getParentJoint" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - result = ((iDynTree::JointSensor const *)arg1)->getParentJoint(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::LinkVelArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkAccArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + arg6 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp6); + result = (bool)iDynTree::predictSensorsMeasurementsFromRawBuffers((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::LinkVelArray const &)*arg3,(iDynTree::LinkAccArray const &)*arg4,(iDynTree::LinkWrenches const &)*arg5,*arg6); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65472,23 +68264,180 @@ int _wrap_JointSensor_getParentJoint(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_JointSensor_getParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_predictSensorsMeasurements__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::SensorsList *arg2 = 0 ; + iDynTree::Traversal *arg3 = 0 ; + iDynTree::FreeFloatingPos *arg4 = 0 ; + iDynTree::FreeFloatingVel *arg5 = 0 ; + iDynTree::FreeFloatingAcc *arg6 = 0 ; + iDynTree::LinAcceleration *arg7 = 0 ; + iDynTree::LinkNetExternalWrenches *arg8 = 0 ; + iDynTree::FreeFloatingAcc *arg9 = 0 ; + iDynTree::LinkPositions *arg10 = 0 ; + iDynTree::LinkVelArray *arg11 = 0 ; + iDynTree::LinkAccArray *arg12 = 0 ; + iDynTree::LinkInternalWrenches *arg13 = 0 ; + iDynTree::FreeFloatingGeneralizedTorques *arg14 = 0 ; + iDynTree::SensorsMeasurements *arg15 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 ; + int res7 = 0 ; + void *argp8 ; + int res8 = 0 ; + void *argp9 = 0 ; + int res9 = 0 ; + void *argp10 = 0 ; + int res10 = 0 ; + void *argp11 = 0 ; + int res11 = 0 ; + void *argp12 = 0 ; + int res12 = 0 ; + void *argp13 = 0 ; + int res13 = 0 ; + void *argp14 = 0 ; + int res14 = 0 ; + void *argp15 = 0 ; + int res15 = 0 ; mxArray * _out; - iDynTree::JointIndex result; + bool result; - if (!SWIG_check_num_args("JointSensor_getParentJointIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("predictSensorsMeasurements",argc,15,15,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_getParentJointIndex" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - result = ((iDynTree::JointSensor const *)arg1)->getParentJointIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + } + arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + arg6 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinAcceleration const &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinAcceleration const &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinAcceleration * >(argp7); + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + arg8 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp8); + res9 = SWIG_ConvertPtr(argv[8], &argp9, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res9)) { + SWIG_exception_fail(SWIG_ArgError(res9), "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + if (!argp9) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + arg9 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp9); + res10 = SWIG_ConvertPtr(argv[9], &argp10, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res10)) { + SWIG_exception_fail(SWIG_ArgError(res10), "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp10) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkPositions &""'"); + } + arg10 = reinterpret_cast< iDynTree::LinkPositions * >(argp10); + res11 = SWIG_ConvertPtr(argv[10], &argp11, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res11)) { + SWIG_exception_fail(SWIG_ArgError(res11), "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp11) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg11 = reinterpret_cast< iDynTree::LinkVelArray * >(argp11); + res12 = SWIG_ConvertPtr(argv[11], &argp12, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res12)) { + SWIG_exception_fail(SWIG_ArgError(res12), "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp12) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg12 = reinterpret_cast< iDynTree::LinkAccArray * >(argp12); + res13 = SWIG_ConvertPtr(argv[12], &argp13, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res13)) { + SWIG_exception_fail(SWIG_ArgError(res13), "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + if (!argp13) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + arg13 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp13); + res14 = SWIG_ConvertPtr(argv[13], &argp14, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 ); + if (!SWIG_IsOK(res14)) { + SWIG_exception_fail(SWIG_ArgError(res14), "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + } + if (!argp14) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + } + arg14 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp14); + res15 = SWIG_ConvertPtr(argv[14], &argp15, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); + if (!SWIG_IsOK(res15)) { + SWIG_exception_fail(SWIG_ArgError(res15), "in method '" "predictSensorsMeasurements" "', argument " "15"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + if (!argp15) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "15"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + arg15 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp15); + result = (bool)iDynTree::predictSensorsMeasurements((iDynTree::Model const &)*arg1,(iDynTree::SensorsList const &)*arg2,(iDynTree::Traversal const &)*arg3,(iDynTree::FreeFloatingPos const &)*arg4,(iDynTree::FreeFloatingVel const &)*arg5,(iDynTree::FreeFloatingAcc const &)*arg6,(iDynTree::GeomVector3 const &)*arg7,(iDynTree::LinkWrenches const &)*arg8,*arg9,*arg10,*arg11,*arg12,*arg13,*arg14,*arg15); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65496,182 +68445,255 @@ int _wrap_JointSensor_getParentJointIndex(int resc, mxArray *resv[], int argc, m } -int _wrap_JointSensor_setParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("JointSensor_setParentJoint",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_setParentJoint" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); +int _wrap_predictSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 14) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[6], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[7], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[8], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[9], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[10], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[11], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[12], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[13], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_predictSensorsMeasurements__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } + } + } + } + } + } + } + } + } } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); + } + if (argc == 15) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[6], &vptr, SWIGTYPE_p_iDynTree__GeomVector3, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[7], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[8], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[9], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[10], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[11], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[12], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[13], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[14], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_predictSensorsMeasurements__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + } + } + } + } + } + } + } + } + } } - arg2 = ptr; } - result = (bool)(arg1)->setParentJoint((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - return 0; -fail: - if (SWIG_IsNewObj(res2)) delete arg2; - return 1; -} - - -int _wrap_JointSensor_setParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - iDynTree::JointIndex *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - iDynTree::JointIndex temp2 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - bool result; - if (!SWIG_check_num_args("JointSensor_setParentJointIndex",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_setParentJointIndex" "', argument " "1"" of type '" "iDynTree::JointSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "JointSensor_setParentJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); - } - temp2 = static_cast< iDynTree::JointIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentJointIndex((iDynTree::JointIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'predictSensorsMeasurements'." + " Possible C/C++ prototypes are:\n" + " iDynTree::predictSensorsMeasurements(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::FreeFloatingAcc const &,iDynTree::LinAcceleration const &,iDynTree::LinkNetExternalWrenches const &,iDynTree::FreeFloatingAcc &,iDynTree::LinkPositions &,iDynTree::LinkVelArray &,iDynTree::LinkAccArray &,iDynTree::LinkInternalWrenches &,iDynTree::FreeFloatingGeneralizedTorques &,iDynTree::SensorsMeasurements &)\n" + " iDynTree::predictSensorsMeasurements(iDynTree::Model const &,iDynTree::SensorsList const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::FreeFloatingAcc const &,iDynTree::LinAcceleration const &,iDynTree::LinkNetExternalWrenches const &,iDynTree::FreeFloatingAcc &,iDynTree::LinkPositions &,iDynTree::LinkVelArray &,iDynTree::LinkAccArray &,iDynTree::LinkInternalWrenches &,iDynTree::FreeFloatingGeneralizedTorques &,iDynTree::SensorsMeasurements &)\n"); return 1; } -int _wrap_JointSensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::JointSensor *arg1 = (iDynTree::JointSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_predictSensorsMeasurementsFromRawBuffers__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::SensorsList *arg2 = 0 ; + iDynTree::Traversal *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::LinkAccArray *arg5 = 0 ; + iDynTree::LinkInternalWrenches *arg6 = 0 ; + iDynTree::SensorsMeasurements *arg7 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("JointSensor_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("predictSensorsMeasurementsFromRawBuffers",argc,7,7,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__JointSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "JointSensor_isConsistent" "', argument " "1"" of type '" "iDynTree::JointSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::JointSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "JointSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "JointSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::JointSensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_delete_LinkSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - - int is_owned; - if (!SWIG_check_num_args("delete_LinkSensor",argc,1,1,0)) { - SWIG_fail; + arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, SWIG_POINTER_DISOWN | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinkSensor" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - if (is_owned) { - delete arg1; + arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); } - _out = (mxArray*)0; - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_LinkSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("LinkSensor_getParentLink",argc,1,1,0)) { - SWIG_fail; + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - result = ((iDynTree::LinkSensor const *)arg1)->getParentLink(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_LinkSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::LinkIndex result; - - if (!SWIG_check_num_args("LinkSensor_getParentLinkIndex",argc,1,1,0)) { - SWIG_fail; + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); + arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::LinkInternalWrenches const &""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - result = ((iDynTree::LinkSensor const *)arg1)->getParentLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "7"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "7"" of type '" "iDynTree::SensorsMeasurements &""'"); + } + arg7 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp7); + result = (bool)iDynTree::predictSensorsMeasurementsFromRawBuffers((iDynTree::Model const &)*arg1,(iDynTree::SensorsList const &)*arg2,(iDynTree::Traversal const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,(iDynTree::LinkWrenches const &)*arg6,*arg7); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65679,96 +68701,150 @@ int _wrap_LinkSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxA } -int _wrap_LinkSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Transform result; - - if (!SWIG_check_num_args("LinkSensor_getLinkSensorTransform",argc,1,1,0)) { - SWIG_fail; +int _wrap_predictSensorsMeasurementsFromRawBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 6) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_predictSensorsMeasurementsFromRawBuffers__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); + if (argc == 7) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__LinkWrenches, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[6], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_predictSensorsMeasurementsFromRawBuffers__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + } + } } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - result = ((iDynTree::LinkSensor const *)arg1)->getLinkSensorTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'predictSensorsMeasurementsFromRawBuffers'." + " Possible C/C++ prototypes are:\n" + " iDynTree::predictSensorsMeasurementsFromRawBuffers(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray const &,iDynTree::LinkInternalWrenches const &,iDynTree::SensorsMeasurements &)\n" + " iDynTree::predictSensorsMeasurementsFromRawBuffers(iDynTree::Model const &,iDynTree::SensorsList const &,iDynTree::Traversal const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray const &,iDynTree::LinkInternalWrenches const &,iDynTree::SensorsMeasurements &)\n"); return 1; } -int _wrap_LinkSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_SolidShapesVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("LinkSensor_setParentLink",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_pop" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + try { + result = (std::vector< iDynTree::SolidShape * >::value_type)std_vector_Sl_iDynTree_SolidShape_Sm__Sg__pop(arg1); } - result = (bool)(arg1)->setParentLink((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_LinkSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_SolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::LinkIndex temp2 ; ptrdiff_t val2 ; int ecode2 = 0 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("LinkSensor_setParentLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_brace" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinkSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_brace" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::difference_type""'"); } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< std::vector< iDynTree::SolidShape * >::difference_type >(val2); + try { + result = (std::vector< iDynTree::SolidShape * >::value_type)std_vector_Sl_iDynTree_SolidShape_Sm__Sg__brace(arg1,arg2); + } + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65776,34 +68852,44 @@ int _wrap_LinkSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxA } -int _wrap_LinkSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_SolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; + std::vector< iDynTree::SolidShape * >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; + ptrdiff_t val3 ; + int ecode3 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("LinkSensor_setLinkSensorTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::LinkSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_setbrace" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_setbrace" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); + ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SolidShapesVector_setbrace" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::difference_type""'"); + } + arg3 = static_cast< std::vector< iDynTree::SolidShape * >::difference_type >(val3); + try { + std_vector_Sl_iDynTree_SolidShape_Sm__Sg__setbrace(arg1,arg2,arg3); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); + } + + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65811,34 +68897,30 @@ int _wrap_LinkSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, } -int _wrap_LinkSensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::LinkSensor *arg1 = (iDynTree::LinkSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SolidShapesVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("LinkSensor_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__LinkSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinkSensor_isConsistent" "', argument " "1"" of type '" "iDynTree::LinkSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_append" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::LinkSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinkSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinkSensor_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_append" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::LinkSensor const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); + std_vector_Sl_iDynTree_SolidShape_Sm__Sg__append(arg1,arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65846,16 +68928,16 @@ int _wrap_LinkSensor_isConsistent(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_SensorsList__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_SolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::SensorsList *result = 0 ; + std::vector< iDynTree::SolidShape * > *result = 0 ; - if (!SWIG_check_num_args("new_SensorsList",argc,0,0,0)) { + if (!SWIG_check_num_args("new_SolidShapesVector",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::SensorsList *)new iDynTree::SensorsList(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 1 | 0 ); + result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65863,75 +68945,78 @@ int _wrap_new_SensorsList__SWIG_0(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_new_SensorsList__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = 0 ; - void *argp1 ; - int res1 = 0 ; +int _wrap_new_SolidShapesVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = 0 ; + int res1 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::SensorsList *result = 0 ; + std::vector< iDynTree::SolidShape * > *result = 0 ; - if (!SWIG_check_num_args("new_SensorsList",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SolidShapesVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsList, 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res1 = swig::asptr(argv[0], &ptr); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const &""'"); + } + arg1 = ptr; } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - result = (iDynTree::SensorsList *)new iDynTree::SensorsList((iDynTree::SensorsList const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsList, 1 | 0 ); + result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >((std::vector< iDynTree::SolidShape * > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res1)) delete arg1; return 0; fail: + if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_new_SensorsList(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SensorsList__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SensorsList__SWIG_1(resc,resv,argc,argv); - } - } +int _wrap_SolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + bool result; - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SensorsList'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsList::SensorsList()\n" - " iDynTree::SensorsList::SensorsList(iDynTree::SensorsList const &)\n"); + if (!SWIG_check_num_args("SolidShapesVector_empty",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_empty" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); + } + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (bool)((std::vector< iDynTree::SolidShape * > const *)arg1)->empty(); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_delete_SensorsList(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; +int _wrap_SolidShapesVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + std::vector< iDynTree::SolidShape * >::size_type result; - int is_owned; - if (!SWIG_check_num_args("delete_SensorsList",argc,1,1,0)) { + if (!SWIG_check_num_args("SolidShapesVector_size",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SensorsList" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_size" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65939,34 +69024,33 @@ int _wrap_delete_SensorsList(int resc, mxArray *resv[], int argc, mxArray *argv[ } -int _wrap_SensorsList_addSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::Sensor *arg2 = 0 ; +int _wrap_SolidShapesVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * > *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - std::ptrdiff_t result; - if (!SWIG_check_num_args("SensorsList_addSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_swap",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_addSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_swap" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Sensor, 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsList_addSensor" "', argument " "2"" of type '" "iDynTree::Sensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * > &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_addSensor" "', argument " "2"" of type '" "iDynTree::Sensor const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * > &""'"); } - arg2 = reinterpret_cast< iDynTree::Sensor * >(argp2); - result = (arg1)->addSensor((iDynTree::Sensor const &)*arg2); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp2); + (arg1)->swap(*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -65974,95 +69058,49 @@ int _wrap_SensorsList_addSensor(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_SensorsList_setSerialization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; +int _wrap_SolidShapesVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - int res3 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("SensorsList_setSerialization",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_setSerialization" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_setSerialization" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - { - std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; - res3 = swig::asptr(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_setSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_setSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); - } - arg3 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_begin" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - result = (bool)(arg1)->setSerialization((iDynTree::SensorType const &)*arg2,(std::vector< std::string,std::allocator< std::string > > const &)*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (arg1)->begin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SensorsList_getSerialization(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; +int _wrap_SolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - void *argp3 = 0 ; - int res3 = 0 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("SensorsList_getSerialization",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_end",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSerialization" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSerialization" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_std__vectorT_std__string_std__allocatorT_std__string_t_t, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSerialization" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_end" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg3 = reinterpret_cast< std::vector< std::string,std::allocator< std::string > > * >(argp3); - result = (bool)(arg1)->getSerialization((iDynTree::SensorType const &)*arg2,*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (arg1)->end(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66070,34 +69108,24 @@ int _wrap_SensorsList_getSerialization(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SensorsList_getNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; +int _wrap_SolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; mxArray * _out; - std::size_t result; + std::vector< iDynTree::SolidShape * >::reverse_iterator result; - if (!SWIG_check_num_args("SensorsList_getNrOfSensors",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_rbegin" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - result = ((iDynTree::SensorsList const *)arg1)->getNrOfSensors((iDynTree::SensorType const &)*arg2); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (arg1)->rbegin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66105,187 +69133,95 @@ int _wrap_SensorsList_getNrOfSensors(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SensorsList_getSensorIndex__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::string *arg3 = 0 ; - std::ptrdiff_t *arg4 = 0 ; +int _wrap_SolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - int res3 = SWIG_OLDOBJ ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::reverse_iterator result; - if (!SWIG_check_num_args("SensorsList_getSensorIndex",argc,4,4,0)) { + if (!SWIG_check_num_args("SolidShapesVector_rend",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensorIndex" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensorIndex" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; - } - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_std__ptrdiff_t, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsList_getSensorIndex" "', argument " "4"" of type '" "std::ptrdiff_t &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "4"" of type '" "std::ptrdiff_t &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_rend" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg4 = reinterpret_cast< std::ptrdiff_t * >(argp4); - result = (bool)((iDynTree::SensorsList const *)arg1)->getSensorIndex((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (arg1)->rend(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SensorsList_getSensorIndex__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::string *arg3 = 0 ; +int _wrap_SolidShapesVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - int res3 = SWIG_OLDOBJ ; mxArray * _out; - std::ptrdiff_t result; - if (!SWIG_check_num_args("SensorsList_getSensorIndex",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_clear",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensorIndex" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensorIndex" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_getSensorIndex" "', argument " "3"" of type '" "std::string const &""'"); - } - arg3 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_clear" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - result = ((iDynTree::SensorsList const *)arg1)->getSensorIndex((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + (arg1)->clear(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SensorsList_getSensorIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsList_getSensorIndex__SWIG_1(resc,resv,argc,argv); - } - } - } +int _wrap_SolidShapesVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + SwigValueWrapper< std::allocator< iDynTree::SolidShape * > > result; + + if (!SWIG_check_num_args("SolidShapesVector_get_allocator",argc,1,1,0)) { + SWIG_fail; } - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_std__ptrdiff_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsList_getSensorIndex__SWIG_0(resc,resv,argc,argv); - } - } - } - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_get_allocator" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsList_getSensorIndex'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsList::getSensorIndex(iDynTree::SensorType const &,std::string const &,std::ptrdiff_t &) const\n" - " iDynTree::SensorsList::getSensorIndex(iDynTree::SensorType const &,std::string const &) const\n"); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< iDynTree::SolidShape * >::allocator_type(static_cast< const std::vector< iDynTree::SolidShape * >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_iDynTree__SolidShape_p_t, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_SensorsList_getSizeOfAllSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_SolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * >::size_type arg1 ; + size_t val1 ; + int ecode1 = 0 ; mxArray * _out; - size_t result; + std::vector< iDynTree::SolidShape * > *result = 0 ; - if (!SWIG_check_num_args("SensorsList_getSizeOfAllSensorsMeasurements",argc,1,1,0)) { + if (!SWIG_check_num_args("new_SolidShapesVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSizeOfAllSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - result = ((iDynTree::SensorsList const *)arg1)->getSizeOfAllSensorsMeasurements(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + } + arg1 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val1); + result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66293,42 +69229,22 @@ int _wrap_SensorsList_getSizeOfAllSensorsMeasurements(int resc, mxArray *resv[], } -int _wrap_SensorsList_getSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t arg3 ; +int _wrap_SolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("SensorsList_getSensor",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_pop_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsList_getSensor" "', argument " "3"" of type '" "std::ptrdiff_t""'"); - } - arg3 = static_cast< std::ptrdiff_t >(val3); - result = (iDynTree::Sensor *)((iDynTree::SensorsList const *)arg1)->getSensor((iDynTree::SensorType const &)*arg2,arg3); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + (arg1)->pop_back(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66336,34 +69252,30 @@ int _wrap_SensorsList_getSensor(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_SensorsList_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_SolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SensorsList_isConsistent",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_isConsistent" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsList_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)((iDynTree::SensorsList const *)arg1)->isConsistent((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + } + arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66371,92 +69283,91 @@ int _wrap_SensorsList_isConsistent(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_SensorsList_removeSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::string *arg3 = 0 ; +int _wrap_SolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - int res3 = SWIG_OLDOBJ ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("SensorsList_removeSensor",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - { - std::string *ptr = (std::string *)0; - res3 = SWIG_AsPtr_std_string(argv[2], &ptr); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::string const &""'"); + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); } - arg3 = ptr; } - result = (bool)(arg1)->removeSensor((iDynTree::SensorType const &)*arg2,(std::string const &)*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SensorsList_removeSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t arg3 ; +int _wrap_SolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::iterator arg2 ; + std::vector< iDynTree::SolidShape * >::iterator arg3 ; void *argp1 = 0 ; - int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; + int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + swig::MatlabSwigIterator *iter3 = 0 ; + int res3 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("SensorsList_removeSensor",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_erase",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeSensor" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsList_removeSensor" "', argument " "3"" of type '" "std::ptrdiff_t""'"); - } - arg3 = static_cast< std::ptrdiff_t >(val3); - result = (bool)(arg1)->removeSensor((iDynTree::SensorType const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res3) || !iter3) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter3); + if (iter_t) { + arg3 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } + } + result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66464,84 +69375,72 @@ int _wrap_SensorsList_removeSensor__SWIG_1(int resc, mxArray *resv[], int argc, } -int _wrap_SensorsList_removeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 3) { +int _wrap_SolidShapesVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - return _wrap_SensorsList_removeSensor__SWIG_1(resc,resv,argc,argv); - } + return _wrap_SolidShapesVector_erase__SWIG_0(resc,resv,argc,argv); } } } if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); - _v = SWIG_CheckState(res); + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); if (_v) { - return _wrap_SensorsList_removeSensor__SWIG_0(resc,resv,argc,argv); + return _wrap_SolidShapesVector_erase__SWIG_1(resc,resv,argc,argv); } } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsList_removeSensor'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_erase'." " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsList::removeSensor(iDynTree::SensorType const &,std::string const &)\n" - " iDynTree::SensorsList::removeSensor(iDynTree::SensorType const &,std::ptrdiff_t const)\n"); + " std::vector< iDynTree::SolidShape * >::erase(std::vector< iDynTree::SolidShape * >::iterator)\n" + " std::vector< iDynTree::SolidShape * >::erase(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::iterator)\n"); return 1; } -int _wrap_SensorsList_removeAllSensorsOfType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; +int _wrap_new_SolidShapesVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * >::size_type arg1 ; + std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; + size_t val1 ; + int ecode1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * > *result = 0 ; - if (!SWIG_check_num_args("SensorsList_removeAllSensorsOfType",argc,2,2,0)) { + if (!SWIG_check_num_args("new_SolidShapesVector",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_removeAllSensorsOfType" "', argument " "1"" of type '" "iDynTree::SensorsList *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_removeAllSensorsOfType" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + } + arg1 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_SolidShapesVector" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); } - result = (bool)(arg1)->removeAllSensorsOfType((iDynTree::SensorType const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); + result = (std::vector< iDynTree::SolidShape * > *)new std::vector< iDynTree::SolidShape * >(arg1,arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66549,31 +69448,78 @@ int _wrap_SensorsList_removeAllSensorsOfType(int resc, mxArray *resv[], int argc } -int _wrap_SensorsList_getSixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - int arg2 ; +int _wrap_new_SolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_SolidShapesVector__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_SolidShapesVector__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SolidShapesVector__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_SolidShapesVector__SWIG_3(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SolidShapesVector'." + " Possible C/C++ prototypes are:\n" + " std::vector< iDynTree::SolidShape * >::vector()\n" + " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * > const &)\n" + " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * >::size_type)\n" + " std::vector< iDynTree::SolidShape * >::vector(std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); + return 1; +} + + +int _wrap_SolidShapesVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::value_type arg2 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::SixAxisForceTorqueSensor *result = 0 ; - if (!SWIG_check_num_args("SensorsList_getSixAxisForceTorqueSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getSixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_push_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getSixAxisForceTorqueSensor" "', argument " "2"" of type '" "int""'"); - } - arg2 = static_cast< int >(val2); - result = (iDynTree::SixAxisForceTorqueSensor *)iDynTree_SensorsList_getSixAxisForceTorqueSensor((iDynTree::SensorsList const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + } + arg2 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp2); + (arg1)->push_back(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66581,31 +69527,23 @@ int _wrap_SensorsList_getSixAxisForceTorqueSensor(int resc, mxArray *resv[], int } -int _wrap_SensorsList_getAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - int arg2 ; +int _wrap_SolidShapesVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::AccelerometerSensor *result = 0 ; + std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("SensorsList_getAccelerometerSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_front" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getAccelerometerSensor" "', argument " "2"" of type '" "int""'"); - } - arg2 = static_cast< int >(val2); - result = (iDynTree::AccelerometerSensor *)iDynTree_SensorsList_getAccelerometerSensor((iDynTree::SensorsList const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (std::vector< iDynTree::SolidShape * >::value_type)((std::vector< iDynTree::SolidShape * > const *)arg1)->front(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66613,31 +69551,23 @@ int _wrap_SensorsList_getAccelerometerSensor(int resc, mxArray *resv[], int argc } -int _wrap_SensorsList_getGyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - int arg2 ; +int _wrap_SolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 = 0 ; mxArray * _out; - iDynTree::GyroscopeSensor *result = 0 ; + std::vector< iDynTree::SolidShape * >::value_type result; - if (!SWIG_check_num_args("SensorsList_getGyroscopeSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getGyroscopeSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_back" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getGyroscopeSensor" "', argument " "2"" of type '" "int""'"); - } - arg2 = static_cast< int >(val2); - result = (iDynTree::GyroscopeSensor *)iDynTree_SensorsList_getGyroscopeSensor((iDynTree::SensorsList const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = (std::vector< iDynTree::SolidShape * >::value_type)((std::vector< iDynTree::SolidShape * > const *)arg1)->back(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66645,31 +69575,38 @@ int _wrap_SensorsList_getGyroscopeSensor(int resc, mxArray *resv[], int argc, mx } -int _wrap_SensorsList_getThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - int arg2 ; +int _wrap_SolidShapesVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::size_type arg2 ; + std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; + size_t val2 ; int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("SensorsList_getThreeAxisAngularAccelerometerSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_assign" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getThreeAxisAngularAccelerometerSensor" "', argument " "2"" of type '" "int""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_assign" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); } - arg2 = static_cast< int >(val2); - result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)iDynTree_SensorsList_getThreeAxisAngularAccelerometerSensor((iDynTree::SensorsList const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); + (arg1)->assign(arg2,arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66677,31 +69614,38 @@ int _wrap_SensorsList_getThreeAxisAngularAccelerometerSensor(int resc, mxArray * } -int _wrap_SensorsList_getThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = (iDynTree::SensorsList *) 0 ; - int arg2 ; +int _wrap_SolidShapesVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::size_type arg2 ; + std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; + size_t val2 ; int ecode2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; - if (!SWIG_check_num_args("SensorsList_getThreeAxisForceTorqueContactSensor",argc,2,2,0)) { + if (!SWIG_check_num_args("SolidShapesVector_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsList, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsList_getThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::SensorsList const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - ecode2 = SWIG_AsVal_int(argv[1], &val2); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsList_getThreeAxisForceTorqueContactSensor" "', argument " "2"" of type '" "int""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); } - arg2 = static_cast< int >(val2); - result = (iDynTree::ThreeAxisForceTorqueContactSensor *)iDynTree_SensorsList_getThreeAxisForceTorqueContactSensor((iDynTree::SensorsList const *)arg1,arg2); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); + res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); + (arg1)->resize(arg2,arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66709,43 +69653,89 @@ int _wrap_SensorsList_getThreeAxisForceTorqueContactSensor(int resc, mxArray *re } -int _wrap_new_SensorsMeasurements__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::SensorsMeasurements *result = 0 ; - - if (!SWIG_check_num_args("new_SensorsMeasurements",argc,0,0,0)) { - SWIG_fail; +int _wrap_SolidShapesVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_SolidShapesVector_resize__SWIG_0(resc,resv,argc,argv); + } + } } - (void)argv; - result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SolidShapesVector_resize__SWIG_1(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_resize'." + " Possible C/C++ prototypes are:\n" + " std::vector< iDynTree::SolidShape * >::resize(std::vector< iDynTree::SolidShape * >::size_type)\n" + " std::vector< iDynTree::SolidShape * >::resize(std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); return 1; } -int _wrap_new_SensorsMeasurements__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsList *arg1 = 0 ; - void *argp1 ; +int _wrap_SolidShapesVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::iterator arg2 ; + std::vector< iDynTree::SolidShape * >::value_type arg3 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; + void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + void *argp3 = 0 ; + int res3 = 0 ; mxArray * _out; - iDynTree::SensorsMeasurements *result = 0 ; + std::vector< iDynTree::SolidShape * >::iterator result; - if (!SWIG_check_num_args("new_SensorsMeasurements",argc,1,1,0)) { + if (!SWIG_check_num_args("SolidShapesVector_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsList, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsList const &""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } } - arg1 = reinterpret_cast< iDynTree::SensorsList * >(argp1); - result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements((iDynTree::SensorsList const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); + res3 = SWIG_ConvertPtr(argv[2], &argp3,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp3); + result = std_vector_Sl_iDynTree_SolidShape_Sm__Sg__insert__SWIG_0(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< iDynTree::SolidShape * >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66753,26 +69743,52 @@ int _wrap_new_SensorsMeasurements__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SensorsMeasurements__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = 0 ; - void *argp1 ; +int _wrap_SolidShapesVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::iterator arg2 ; + std::vector< iDynTree::SolidShape * >::size_type arg3 ; + std::vector< iDynTree::SolidShape * >::value_type arg4 = (std::vector< iDynTree::SolidShape * >::value_type) 0 ; + void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + size_t val3 ; + int ecode3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - iDynTree::SensorsMeasurements *result = 0 ; - if (!SWIG_check_num_args("new_SensorsMeasurements",argc,1,1,0)) { + if (!SWIG_check_num_args("SolidShapesVector_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const &""'"); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } else { + swig::MatlabSwigIterator_T::iterator > *iter_t = dynamic_cast::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "SolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::iterator""'"); + } } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - result = (iDynTree::SensorsMeasurements *)new iDynTree::SensorsMeasurements((iDynTree::SensorsMeasurements const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SensorsMeasurements, 1 | 0 ); + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + } + arg3 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val3); + res4 = SWIG_ConvertPtr(argv[3], &argp4,SWIGTYPE_p_iDynTree__SolidShape, 0 | 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< iDynTree::SolidShape * >::value_type""'"); + } + arg4 = reinterpret_cast< std::vector< iDynTree::SolidShape * >::value_type >(argp4); + std_vector_Sl_iDynTree_SolidShape_Sm__Sg__insert__SWIG_1(arg1,arg2,arg3,arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66780,57 +69796,81 @@ int _wrap_new_SensorsMeasurements__SWIG_2(int resc, mxArray *resv[], int argc, m } -int _wrap_new_SensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SensorsMeasurements__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { +int _wrap_SolidShapesVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SensorsMeasurements__SWIG_1(resc,resv,argc,argv); + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SolidShapesVector_insert__SWIG_0(resc,resv,argc,argv); + } + } } } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); + if (argc == 4) { + int _v; + int res = swig::asptr(argv[0], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_new_SensorsMeasurements__SWIG_2(resc,resv,argc,argv); + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast::iterator > *>(iter) != 0)); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__SolidShape, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_SolidShapesVector_insert__SWIG_1(resc,resv,argc,argv); + } + } + } } } - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SensorsMeasurements'." + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SolidShapesVector_insert'." " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsMeasurements::SensorsMeasurements()\n" - " iDynTree::SensorsMeasurements::SensorsMeasurements(iDynTree::SensorsList const &)\n" - " iDynTree::SensorsMeasurements::SensorsMeasurements(iDynTree::SensorsMeasurements const &)\n"); + " std::vector< iDynTree::SolidShape * >::insert(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::value_type)\n" + " std::vector< iDynTree::SolidShape * >::insert(std::vector< iDynTree::SolidShape * >::iterator,std::vector< iDynTree::SolidShape * >::size_type,std::vector< iDynTree::SolidShape * >::value_type)\n"); return 1; } -int _wrap_delete_SensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; +int _wrap_SolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; + std::vector< iDynTree::SolidShape * >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_SensorsMeasurements",argc,1,1,0)) { + if (!SWIG_check_num_args("SolidShapesVector_reserve",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_reserve" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SolidShapesVector_reserve" "', argument " "2"" of type '" "std::vector< iDynTree::SolidShape * >::size_type""'"); + } + arg2 = static_cast< std::vector< iDynTree::SolidShape * >::size_type >(val2); + (arg1)->reserve(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -66839,42 +69879,23 @@ int _wrap_delete_SensorsMeasurements(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SensorsMeasurements_setNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::size_t arg3 ; +int _wrap_SolidShapesVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - size_t val3 ; - int ecode3 = 0 ; mxArray * _out; - bool result; + std::vector< iDynTree::SolidShape * >::size_type result; - if (!SWIG_check_num_args("SensorsMeasurements_setNrOfSensors",argc,3,3,0)) { + if (!SWIG_check_num_args("SolidShapesVector_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SolidShapesVector_capacity" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > const *""'"); } - ecode3 = SWIG_AsVal_size_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setNrOfSensors" "', argument " "3"" of type '" "std::size_t""'"); - } - arg3 = static_cast< std::size_t >(val3); - result = (bool)(arg1)->setNrOfSensors((iDynTree::SensorType const &)*arg2,arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + result = ((std::vector< iDynTree::SolidShape * > const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66882,34 +69903,26 @@ int _wrap_SensorsMeasurements_setNrOfSensors(int resc, mxArray *resv[], int argc } -int _wrap_SensorsMeasurements_getNrOfSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; +int _wrap_delete_SolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< iDynTree::SolidShape * > *arg1 = (std::vector< iDynTree::SolidShape * > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; mxArray * _out; - std::size_t result; - if (!SWIG_check_num_args("SensorsMeasurements_getNrOfSensors",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_SolidShapesVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getNrOfSensors" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SolidShapesVector" "', argument " "1"" of type '" "std::vector< iDynTree::SolidShape * > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getNrOfSensors" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + arg1 = reinterpret_cast< std::vector< iDynTree::SolidShape * > * >(argp1); + if (is_owned) { + delete arg1; } - result = ((iDynTree::SensorsMeasurements const *)arg1)->getNrOfSensors((iDynTree::SensorType const &)*arg2); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66917,34 +69930,29 @@ int _wrap_SensorsMeasurements_getNrOfSensors(int resc, mxArray *resv[], int argc } -int _wrap_SensorsMeasurements_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorsList *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_pop(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type result; - if (!SWIG_check_num_args("SensorsMeasurements_resize",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_pop",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_resize" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_pop" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsMeasurements_resize" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + try { + result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__pop(arg1); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_resize" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); - result = (bool)(arg1)->resize((iDynTree::SensorsList const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + + _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66952,34 +69960,37 @@ int _wrap_SensorsMeasurements_resize(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_SensorsMeasurements_toVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_brace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::difference_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + ptrdiff_t val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type result; - if (!SWIG_check_num_args("SensorsMeasurements_toVector",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_brace",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_toVector" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_brace" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SensorsMeasurements_toVector" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_brace" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::difference_type""'"); + } + arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::difference_type >(val2); + try { + result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__brace(arg1,arg2); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_toVector" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->toVector(*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + + _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -66987,55 +69998,46 @@ int _wrap_SensorsMeasurements_toVector(int resc, mxArray *resv[], int argc, mxAr } -int _wrap_SensorsMeasurements_setMeasurement__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t *arg3 = 0 ; - iDynTree::Wrench *arg4 = 0 ; +int _wrap_LinksSolidShapesVector_setbrace(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::difference_type arg3 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - std::ptrdiff_t temp3 ; ptrdiff_t val3 ; int ecode3 = 0 ; - void *argp4 ; - int res4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SensorsMeasurements_setMeasurement",argc,4,4,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_setbrace",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + int res = swig::asptr(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; } ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinksSolidShapesVector_setbrace" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::difference_type""'"); } - temp3 = static_cast< std::ptrdiff_t >(val3); - arg3 = &temp3; - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench const &""'"); + arg3 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::difference_type >(val3); + try { + std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__setbrace(arg1,arg2,arg3); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench const &""'"); + catch(std::out_of_range &_e) { + SWIG_exception_fail(SWIG_IndexError, (&_e)->what()); } - arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); - result = (bool)(arg1)->setMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,(iDynTree::Wrench const &)*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67043,55 +70045,49 @@ int _wrap_SensorsMeasurements_setMeasurement__SWIG_0(int resc, mxArray *resv[], } -int _wrap_SensorsMeasurements_setMeasurement__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t *arg3 = 0 ; - iDynTree::Vector3 *arg4 = 0 ; +int _wrap_LinksSolidShapesVector_append(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - std::ptrdiff_t temp3 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - void *argp4 ; - int res4 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SensorsMeasurements_setMeasurement",argc,4,4,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_append",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_append" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); - } - temp3 = static_cast< std::ptrdiff_t >(val3); - arg3 = &temp3; - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 const &""'"); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + int res = swig::asptr(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "LinksSolidShapesVector_append" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_setMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 const &""'"); + std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__append(arg1,arg2); + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinksSolidShapesVector__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; + + if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,0,0,0)) { + SWIG_fail; } - arg4 = reinterpret_cast< iDynTree::Vector3 * >(argp4); - result = (bool)(arg1)->setMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,(iDynTree::Vector3 const &)*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + (void)argv; + result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67099,116 +70095,53 @@ int _wrap_SensorsMeasurements_setMeasurement__SWIG_1(int resc, mxArray *resv[], } -int _wrap_SensorsMeasurements_setMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsMeasurements_setMeasurement__SWIG_0(resc,resv,argc,argv); - } - } - } - } +int _wrap_new_LinksSolidShapesVector__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *arg1 = 0 ; + int res1 = SWIG_OLDOBJ ; + mxArray * _out; + std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; + + if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,1,1,0)) { + SWIG_fail; } - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsMeasurements_setMeasurement__SWIG_1(resc,resv,argc,argv); - } - } - } + { + std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > *ptr = (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > *)0; + res1 = swig::asptr(argv[0], &ptr); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &""'"); } + arg1 = ptr; } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsMeasurements_setMeasurement'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsMeasurements::setMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Wrench const &)\n" - " iDynTree::SensorsMeasurements::setMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Vector3 const &)\n"); + result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >((std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res1)) delete arg1; + return 0; +fail: + if (SWIG_IsNewObj(res1)) delete arg1; return 1; } -int _wrap_SensorsMeasurements_getMeasurement__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t *arg3 = 0 ; - iDynTree::Wrench *arg4 = 0 ; +int _wrap_LinksSolidShapesVector_empty(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - std::ptrdiff_t temp3 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SensorsMeasurements_getMeasurement",argc,4,4,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_empty",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; - } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); - } - temp3 = static_cast< std::ptrdiff_t >(val3); - arg3 = &temp3; - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_empty" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); - result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->getMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,*arg4); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (bool)((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->empty(); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -67217,55 +70150,57 @@ int _wrap_SensorsMeasurements_getMeasurement__SWIG_0(int resc, mxArray *resv[], } -int _wrap_SensorsMeasurements_getMeasurement__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; - iDynTree::SensorType *arg2 = 0 ; - std::ptrdiff_t *arg3 = 0 ; - iDynTree::Vector3 *arg4 = 0 ; +int _wrap_LinksSolidShapesVector_size(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int val2 ; - int ecode2 ; - iDynTree::SensorType temp2 ; - std::ptrdiff_t temp3 ; - ptrdiff_t val3 ; - int ecode3 = 0 ; - void *argp4 = 0 ; - int res4 = 0 ; mxArray * _out; - bool result; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type result; - if (!SWIG_check_num_args("SensorsMeasurements_getMeasurement",argc,4,4,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_size",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_size" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - ecode2 = SWIG_AsVal_int (argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "2"" of type '" "iDynTree::SensorType const &""'"); - } else { - temp2 = static_cast< iDynTree::SensorType >(val2); - arg2 = &temp2; + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->size(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_LinksSolidShapesVector_swap(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("LinksSolidShapesVector_swap",argc,2,2,0)) { + SWIG_fail; } - ecode3 = SWIG_AsVal_ptrdiff_t(argv[2], &val3); - if (!SWIG_IsOK(ecode3)) { - SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "3"" of type '" "std::ptrdiff_t""'"); - } - temp3 = static_cast< std::ptrdiff_t >(val3); - arg3 = &temp3; - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 &""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_swap" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinksSolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > &""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SensorsMeasurements_getMeasurement" "', argument " "4"" of type '" "iDynTree::Vector3 &""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_swap" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > &""'"); } - arg4 = reinterpret_cast< iDynTree::Vector3 * >(argp4); - result = (bool)((iDynTree::SensorsMeasurements const *)arg1)->getMeasurement((iDynTree::SensorType const &)*arg2,(std::ptrdiff_t const &)*arg3,*arg4); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > * >(argp2); + (arg1)->swap(*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67273,85 +70208,24 @@ int _wrap_SensorsMeasurements_getMeasurement__SWIG_1(int resc, mxArray *resv[], } -int _wrap_SensorsMeasurements_getMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__Wrench, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsMeasurements_getMeasurement__SWIG_0(resc,resv,argc,argv); - } - } - } - } - } - if (argc == 4) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0); - _v = SWIG_CheckState(res); - if (_v) { - { - int res = SWIG_AsVal_int(argv[1], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - { - int res = SWIG_AsVal_ptrdiff_t(argv[2], NULL); - _v = SWIG_CheckState(res); - } - if (_v) { - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_SensorsMeasurements_getMeasurement__SWIG_1(resc,resv,argc,argv); - } - } - } - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'SensorsMeasurements_getMeasurement'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SensorsMeasurements::getMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Wrench &) const\n" - " iDynTree::SensorsMeasurements::getMeasurement(iDynTree::SensorType const &,std::ptrdiff_t const &,iDynTree::Vector3 &) const\n"); - return 1; -} - - -int _wrap_SensorsMeasurements_getSizeOfAllSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SensorsMeasurements *arg1 = (iDynTree::SensorsMeasurements *) 0 ; +int _wrap_LinksSolidShapesVector_begin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - size_t result; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("SensorsMeasurements_getSizeOfAllSensorsMeasurements",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_begin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SensorsMeasurements_getSizeOfAllSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::SensorsMeasurements const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_begin" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp1); - result = ((iDynTree::SensorsMeasurements const *)arg1)->getSizeOfAllSensorsMeasurements(); - _out = SWIG_From_size_t(static_cast< size_t >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (arg1)->begin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67359,16 +70233,24 @@ int _wrap_SensorsMeasurements_getSizeOfAllSensorsMeasurements(int resc, mxArray } -int _wrap_new_SixAxisForceTorqueSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_LinksSolidShapesVector_end(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::SixAxisForceTorqueSensor *result = 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("new_SixAxisForceTorqueSensor",argc,0,0,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_end",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::SixAxisForceTorqueSensor *)new iDynTree::SixAxisForceTorqueSensor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_end" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); + } + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (arg1)->end(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67376,26 +70258,24 @@ int _wrap_new_SixAxisForceTorqueSensor__SWIG_0(int resc, mxArray *resv[], int ar } -int _wrap_new_SixAxisForceTorqueSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = 0 ; - void *argp1 ; +int _wrap_LinksSolidShapesVector_rbegin(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SixAxisForceTorqueSensor *result = 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator result; - if (!SWIG_check_num_args("new_SixAxisForceTorqueSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_rbegin",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const &""'"); - } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_rbegin" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = (iDynTree::SixAxisForceTorqueSensor *)new iDynTree::SixAxisForceTorqueSensor((iDynTree::SixAxisForceTorqueSensor const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 1 | 0 ); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (arg1)->rbegin(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67403,47 +70283,46 @@ int _wrap_new_SixAxisForceTorqueSensor__SWIG_1(int resc, mxArray *resv[], int ar } -int _wrap_new_SixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_SixAxisForceTorqueSensor__SWIG_0(resc,resv,argc,argv); +int _wrap_LinksSolidShapesVector_rend(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator result; + + if (!SWIG_check_num_args("LinksSolidShapesVector_rend",argc,1,1,0)) { + SWIG_fail; } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_SixAxisForceTorqueSensor__SWIG_1(resc,resv,argc,argv); - } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_rend" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_SixAxisForceTorqueSensor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::SixAxisForceTorqueSensor::SixAxisForceTorqueSensor()\n" - " iDynTree::SixAxisForceTorqueSensor::SixAxisForceTorqueSensor(iDynTree::SixAxisForceTorqueSensor const &)\n"); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (arg1)->rend(); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::reverse_iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); + if (_out) --resc, *resv++ = _out; + return 0; +fail: return 1; } -int _wrap_delete_SixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_clear(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_SixAxisForceTorqueSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_clear",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_SixAxisForceTorqueSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_clear" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + (arg1)->clear(); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -67452,81 +70331,70 @@ int _wrap_delete_SixAxisForceTorqueSensor(int resc, mxArray *resv[], int argc, m } -int _wrap_SixAxisForceTorqueSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_get_allocator(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + SwigValueWrapper< std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_get_allocator",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_get_allocator" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->get_allocator(); + _out = SWIG_NewPointerObj((new std::vector< std::vector< iDynTree::SolidShape * > >::allocator_type(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::allocator_type& >(result))), SWIGTYPE_p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t, SWIG_POINTER_OWN | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_new_LinksSolidShapesVector__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg1 ; + size_t val1 ; + int ecode1 = 0 ; + mxArray * _out; + std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; + + if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,1,1,0)) { + SWIG_fail; } - result = (bool)(arg1)->setName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + } + arg1 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val1); + result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_SixAxisForceTorqueSensor_setFirstLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Transform *arg3 = 0 ; +int _wrap_LinksSolidShapesVector_pop_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setFirstLinkSensorTransform",argc,3,3,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_pop_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setFirstLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_pop_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->setFirstLinkSensorTransform(arg2,(iDynTree::Transform const &)*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + (arg1)->pop_back(); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67534,42 +70402,30 @@ int _wrap_SixAxisForceTorqueSensor_setFirstLinkSensorTransform(int resc, mxArray } -int _wrap_SixAxisForceTorqueSensor_setSecondLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Transform *arg3 = 0 ; +int _wrap_LinksSolidShapesVector_resize__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; - ptrdiff_t val2 ; + size_t val2 ; int ecode2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setSecondLinkSensorTransform",argc,3,3,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setSecondLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); - } - arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->setSecondLinkSensorTransform(arg2,(iDynTree::Transform const &)*arg3); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); + (arg1)->resize(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67577,23 +70433,38 @@ int _wrap_SixAxisForceTorqueSensor_setSecondLinkSensorTransform(int resc, mxArra } -int _wrap_SixAxisForceTorqueSensor_getFirstLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_erase__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; mxArray * _out; - iDynTree::LinkIndex result; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getFirstLinkIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_erase",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getFirstLinkIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getFirstLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } else { + swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } + } + result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__erase__SWIG_0(arg1,arg2); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67601,23 +70472,52 @@ int _wrap_SixAxisForceTorqueSensor_getFirstLinkIndex(int resc, mxArray *resv[], } -int _wrap_SixAxisForceTorqueSensor_getSecondLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_erase__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg3 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + swig::MatlabSwigIterator *iter3 = 0 ; + int res3 ; mxArray * _out; - iDynTree::LinkIndex result; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSecondLinkIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_erase",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSecondLinkIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_erase" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSecondLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } else { + swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } + } + res3 = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter3), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res3) || !iter3) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } else { + swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter3); + if (iter_t) { + arg3 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_erase" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } + } + result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__erase__SWIG_1(arg1,arg2,arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67625,75 +70525,162 @@ int _wrap_SixAxisForceTorqueSensor_getSecondLinkIndex(int resc, mxArray *resv[], } -int _wrap_SixAxisForceTorqueSensor_setFirstLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_LinksSolidShapesVector_erase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_LinksSolidShapesVector_erase__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[2], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); + if (_v) { + return _wrap_LinksSolidShapesVector_erase__SWIG_1(resc,resv,argc,argv); + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_erase'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::erase(std::vector< std::vector< iDynTree::SolidShape * > >::iterator)\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::erase(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::iterator)\n"); + return 1; +} + + +int _wrap_new_LinksSolidShapesVector__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg1 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg2 = 0 ; + size_t val1 ; + int ecode1 = 0 ; int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + std::vector< std::vector< iDynTree::SolidShape * > > *result = 0 ; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setFirstLinkName",argc,2,2,0)) { + if (!SWIG_check_num_args("new_LinksSolidShapesVector",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + ecode1 = SWIG_AsVal_size_t(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "new_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + } + arg1 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val1); { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res2 = swig::asptr(argv[1], &ptr); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "new_LinksSolidShapesVector" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setFirstLinkName" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_LinksSolidShapesVector" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + arg2 = ptr; + } + result = (std::vector< std::vector< iDynTree::SolidShape * > > *)new std::vector< std::vector< iDynTree::SolidShape * > >(arg1,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + return 1; +} + + +int _wrap_new_LinksSolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_LinksSolidShapesVector__SWIG_0(resc,resv,argc,argv); + } + if (argc == 1) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_new_LinksSolidShapesVector__SWIG_2(resc,resv,argc,argv); + } + } + if (argc == 1) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinksSolidShapesVector__SWIG_1(resc,resv,argc,argv); + } + } + if (argc == 2) { + int _v; + { + int res = SWIG_AsVal_size_t(argv[0], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = swig::asptr(argv[1], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_LinksSolidShapesVector__SWIG_3(resc,resv,argc,argv); + } } - arg2 = ptr; } - result = (bool)(arg1)->setFirstLinkName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - return 0; -fail: - if (SWIG_IsNewObj(res2)) delete arg2; + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_LinksSolidShapesVector'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::vector()\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > const &)\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape * > >::size_type)\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::vector(std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); return 1; } -int _wrap_SixAxisForceTorqueSensor_setSecondLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_push_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setSecondLinkName",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_push_back",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_push_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res2 = swig::asptr(argv[1], &ptr); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "LinksSolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setSecondLinkName" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_push_back" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); } arg2 = ptr; } - result = (bool)(arg1)->setSecondLinkName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + (arg1)->push_back((std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; if (SWIG_IsNewObj(res2)) delete arg2; return 0; @@ -67703,23 +70690,23 @@ int _wrap_SixAxisForceTorqueSensor_setSecondLinkName(int resc, mxArray *resv[], } -int _wrap_SixAxisForceTorqueSensor_getFirstLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_front(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *result = 0 ; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getFirstLinkName",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_front",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getFirstLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_front" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getFirstLinkName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (std::vector< std::vector< iDynTree::SolidShape * > >::value_type *) &((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->front(); + _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(*result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67727,23 +70714,23 @@ int _wrap_SixAxisForceTorqueSensor_getFirstLinkName(int resc, mxArray *resv[], i } -int _wrap_SixAxisForceTorqueSensor_getSecondLinkName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_back(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *result = 0 ; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSecondLinkName",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_back",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSecondLinkName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_back" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSecondLinkName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = (std::vector< std::vector< iDynTree::SolidShape * > >::value_type *) &((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->back(); + _out = swig::from(static_cast< std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > >(*result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67751,200 +70738,328 @@ int _wrap_SixAxisForceTorqueSensor_getSecondLinkName(int resc, mxArray *resv[], } -int _wrap_SixAxisForceTorqueSensor_setParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_assign(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + size_t val2 ; + int ecode2 = 0 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setParentJoint",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_assign",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_assign" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_assign" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + } + arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); } if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_setParentJoint" "', argument " "2"" of type '" "std::string const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_assign" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); } - arg2 = ptr; + arg3 = ptr; } - result = (bool)(arg1)->setParentJoint((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + (arg1)->assign(arg2,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SixAxisForceTorqueSensor_setParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::JointIndex *arg2 = 0 ; +int _wrap_LinksSolidShapesVector_resize__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::JointIndex temp2 ; - ptrdiff_t val2 ; + size_t val2 ; int ecode2 = 0 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setParentJointIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_resize",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setParentJointIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_resize" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setParentJointIndex" "', argument " "2"" of type '" "iDynTree::JointIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_resize" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); } - temp2 = static_cast< iDynTree::JointIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentJointIndex((iDynTree::JointIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_resize" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + arg3 = ptr; + } + (arg1)->resize(arg2,(std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SixAxisForceTorqueSensor_setAppliedWrenchLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_setAppliedWrenchLink",argc,2,2,0)) { - SWIG_fail; +int _wrap_LinksSolidShapesVector_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_LinksSolidShapesVector_resize__SWIG_0(resc,resv,argc,argv); + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_setAppliedWrenchLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = swig::asptr(argv[2], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinksSolidShapesVector_resize__SWIG_1(resc,resv,argc,argv); + } + } + } } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_setAppliedWrenchLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (bool)(arg1)->setAppliedWrenchLink(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_resize'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::resize(std::vector< std::vector< iDynTree::SolidShape * > >::size_type)\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::resize(std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); return 1; } -int _wrap_SixAxisForceTorqueSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_insert__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - std::string result; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_insert",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getName" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } else { + swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } + } + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + arg3 = ptr; + } + result = std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_0(arg1,arg2,(std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > const &)*arg3); + _out = SWIG_NewPointerObj(swig::make_output_iterator(static_cast< const std::vector< std::vector< iDynTree::SolidShape * > >::iterator & >(result)), + swig::MatlabSwigIterator::descriptor(),SWIG_POINTER_OWN); if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_SixAxisForceTorqueSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_insert__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::iterator arg2 ; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg3 ; + std::vector< std::vector< iDynTree::SolidShape * > >::value_type *arg4 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + swig::MatlabSwigIterator *iter2 = 0 ; + int res2 ; + size_t val3 ; + int ecode3 = 0 ; + int res4 = SWIG_OLDOBJ ; mxArray * _out; - iDynTree::SensorType result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_insert",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_insert" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter2), swig::MatlabSwigIterator::descriptor(), 0); + if (!SWIG_IsOK(res2) || !iter2) { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } else { + swig::MatlabSwigIterator_T >::iterator > *iter_t = dynamic_cast >::iterator > *>(iter2); + if (iter_t) { + arg2 = iter_t->get_current(); + } else { + SWIG_exception_fail(SWIG_ArgError(SWIG_TypeError), "in method '" "LinksSolidShapesVector_insert" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::iterator""'"); + } + } + ecode3 = SWIG_AsVal_size_t(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "LinksSolidShapesVector_insert" "', argument " "3"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + } + arg3 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val3); + { + std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *ptr = (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > > *)0; + res4 = swig::asptr(argv[3], &ptr); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "LinksSolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "LinksSolidShapesVector_insert" "', argument " "4"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &""'"); + } + arg4 = ptr; + } + std_vector_Sl_std_vector_Sl_iDynTree_SolidShape_Sm__Sg__Sg__insert__SWIG_1(arg1,arg2,arg3,(std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > const &)*arg4); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res4)) delete arg4; return 0; fail: + if (SWIG_IsNewObj(res4)) delete arg4; return 1; } -int _wrap_SixAxisForceTorqueSensor_getParentJoint(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getParentJoint",argc,1,1,0)) { - SWIG_fail; +int _wrap_LinksSolidShapesVector_insert(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 3) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); + if (_v) { + int res = swig::asptr(argv[2], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinksSolidShapesVector_insert__SWIG_0(resc,resv,argc,argv); + } + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getParentJoint" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + if (argc == 4) { + int _v; + int res = swig::asptr(argv[0], (std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + swig::MatlabSwigIterator *iter = 0; + int res = SWIG_ConvertPtr(argv[1], SWIG_as_voidptrptr(&iter), swig::MatlabSwigIterator::descriptor(), 0); + _v = (SWIG_IsOK(res) && iter && (dynamic_cast >::iterator > *>(iter) != 0)); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[2], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + int res = swig::asptr(argv[3], (std::vector< iDynTree::SolidShape*,std::allocator< iDynTree::SolidShape * > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_LinksSolidShapesVector_insert__SWIG_1(resc,resv,argc,argv); + } + } + } + } } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getParentJoint(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'LinksSolidShapesVector_insert'." + " Possible C/C++ prototypes are:\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::insert(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n" + " std::vector< std::vector< iDynTree::SolidShape * > >::insert(std::vector< std::vector< iDynTree::SolidShape * > >::iterator,std::vector< std::vector< iDynTree::SolidShape * > >::size_type,std::vector< std::vector< iDynTree::SolidShape * > >::value_type const &)\n"); return 1; } -int _wrap_SixAxisForceTorqueSensor_getParentJointIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_reserve(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::JointIndex result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getParentJointIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_reserve",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getParentJointIndex" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_reserve" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getParentJointIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "LinksSolidShapesVector_reserve" "', argument " "2"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > >::size_type""'"); + } + arg2 = static_cast< std::vector< std::vector< iDynTree::SolidShape * > >::size_type >(val2); + (arg1)->reserve(arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67952,23 +71067,23 @@ int _wrap_SixAxisForceTorqueSensor_getParentJointIndex(int resc, mxArray *resv[] } -int _wrap_SixAxisForceTorqueSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_LinksSolidShapesVector_capacity(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - bool result; + std::vector< std::vector< iDynTree::SolidShape * > >::size_type result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("LinksSolidShapesVector_capacity",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_isValid" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "LinksSolidShapesVector_capacity" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > const *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + result = ((std::vector< std::vector< iDynTree::SolidShape * > > const *)arg1)->capacity(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -67976,23 +71091,26 @@ int _wrap_SixAxisForceTorqueSensor_isValid(int resc, mxArray *resv[], int argc, } -int _wrap_SixAxisForceTorqueSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_delete_LinksSolidShapesVector(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + std::vector< std::vector< iDynTree::SolidShape * > > *arg1 = (std::vector< std::vector< iDynTree::SolidShape * > > *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_clone",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_LinksSolidShapesVector",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_clone" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_LinksSolidShapesVector" "', argument " "1"" of type '" "std::vector< std::vector< iDynTree::SolidShape * > > *""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< std::vector< std::vector< iDynTree::SolidShape * > > * >(argp1); + if (is_owned) { + delete arg1; + } + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68000,33 +71118,69 @@ int _wrap_SixAxisForceTorqueSensor_clone(int resc, mxArray *resv[], int argc, mx } -int _wrap_SixAxisForceTorqueSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardPositionKinematics__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::Transform *arg3 = 0 ; + iDynTree::VectorDynSize *arg4 = 0 ; + iDynTree::LinkPositions *arg5 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("ForwardPositionKinematics",argc,5,5,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::Transform const &""'"); + } + arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPositionKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); + result = (bool)iDynTree::ForwardPositionKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::Transform const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,*arg5); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68035,23 +71189,59 @@ int _wrap_SixAxisForceTorqueSensor_updateIndices(int resc, mxArray *resv[], int } -int _wrap_SixAxisForceTorqueSensor_getAppliedWrenchLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_ForwardPositionKinematics__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::LinkPositions *arg4 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getAppliedWrenchLink",argc,1,1,0)) { + if (!SWIG_check_num_args("ForwardPositionKinematics",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getAppliedWrenchLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getAppliedWrenchLink(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPositionKinematics" "', argument " "4"" of type '" "iDynTree::LinkPositions &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkPositions * >(argp4); + result = (bool)iDynTree::ForwardPositionKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68059,73 +71249,154 @@ int _wrap_SixAxisForceTorqueSensor_getAppliedWrenchLink(int resc, mxArray *resv[ } -int _wrap_SixAxisForceTorqueSensor_isLinkAttachedToSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - void *argp1 = 0 ; - int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_isLinkAttachedToSensor",argc,2,2,0)) { - SWIG_fail; +int _wrap_ForwardPositionKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 4) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ForwardPositionKinematics__SWIG_1(resc,resv,argc,argv); + } + } + } + } } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_isLinkAttachedToSensor" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + if (argc == 5) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__Transform, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__VectorDynSize, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkPositions, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ForwardPositionKinematics__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_isLinkAttachedToSensor" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->isLinkAttachedToSensor(arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ForwardPositionKinematics'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ForwardPositionKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::Transform const &,iDynTree::VectorDynSize const &,iDynTree::LinkPositions &)\n" + " iDynTree::ForwardPositionKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::LinkPositions &)\n"); return 1; } -int _wrap_SixAxisForceTorqueSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Transform *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardVelAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::FreeFloatingAcc *arg5 = 0 ; + iDynTree::LinkVelArray *arg6 = 0 ; + iDynTree::LinkAccArray *arg7 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getLinkSensorTransform",argc,3,3,0)) { + if (!SWIG_check_num_args("ForwardVelAccKinematics",argc,7,7,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getLinkSensorTransform" "', argument " "3"" of type '" "iDynTree::Transform &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } - arg3 = reinterpret_cast< iDynTree::Transform * >(argp3); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getLinkSensorTransform(arg2,*arg3); + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); + result = (bool)iDynTree::ForwardVelAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,*arg6,*arg7); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68134,52 +71405,102 @@ int _wrap_SixAxisForceTorqueSensor_getLinkSensorTransform(int resc, mxArray *res } -int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Wrench *arg3 = 0 ; - iDynTree::Wrench *arg4 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardPosVelAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::FreeFloatingAcc *arg5 = 0 ; + iDynTree::LinkPositions *arg6 = 0 ; + iDynTree::LinkVelArray *arg7 = 0 ; + iDynTree::LinkAccArray *arg8 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; + void *argp2 ; + int res2 = 0 ; void *argp3 ; int res3 = 0 ; - void *argp4 = 0 ; + void *argp4 ; int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; + void *argp8 = 0 ; + int res8 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLink",argc,4,4,0)) { + if (!SWIG_check_num_args("ForwardPosVelAccKinematics",argc,8,8,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPosVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPosVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPosVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "3"" of type '" "iDynTree::Wrench const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } - arg3 = reinterpret_cast< iDynTree::Wrench * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__Wrench, 0 ); + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPosVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLink" "', argument " "4"" of type '" "iDynTree::Wrench &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); } - arg4 = reinterpret_cast< iDynTree::Wrench * >(argp4); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLink(arg2,(iDynTree::Wrench const &)*arg3,*arg4); + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPosVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardPosVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkPositions &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkPositions * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardPosVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkVelArray * >(argp7); + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "ForwardPosVelAccKinematics" "', argument " "8"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelAccKinematics" "', argument " "8"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg8 = reinterpret_cast< iDynTree::LinkAccArray * >(argp8); + result = (bool)iDynTree::ForwardPosVelAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,*arg6,*arg7,*arg8); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68188,41 +71509,80 @@ int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLink(int resc, mxArray *res } -int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Matrix6x6 *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardPosVelKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::LinkPositions *arg5 = 0 ; + iDynTree::LinkVelArray *arg6 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix",argc,3,3,0)) { + if (!SWIG_check_num_args("ForwardPosVelKinematics",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardPosVelKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardPosVelKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardPosVelKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } - arg3 = reinterpret_cast< iDynTree::Matrix6x6 * >(argp3); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLinkMatrix(arg2,*arg3); + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardPosVelKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardPosVelKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "5"" of type '" "iDynTree::LinkPositions &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkPositions * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardPosVelKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardPosVelKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); + result = (bool)iDynTree::ForwardPosVelKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,*arg5,*arg6); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68231,41 +71591,91 @@ int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix(int resc, mxArra } -int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::LinkIndex arg2 ; - iDynTree::Matrix6x6 *arg3 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::FreeFloatingAcc *arg5 = 0 ; + iDynTree::LinkVelArray *arg6 = 0 ; + iDynTree::LinkAccArray *arg7 = 0 ; + void *argp1 ; int res1 = 0 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - void *argp3 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix",argc,3,3,0)) { + if (!SWIG_check_num_args("ForwardAccKinematics",argc,7,7,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "5"" of type '" "iDynTree::FreeFloatingAcc const &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - arg2 = static_cast< iDynTree::LinkIndex >(val2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__MatrixFixSizeT_6_6_t, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); + arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix" "', argument " "3"" of type '" "iDynTree::Matrix6x6 &""'"); + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); } - arg3 = reinterpret_cast< iDynTree::Matrix6x6 * >(argp3); - result = (bool)((iDynTree::SixAxisForceTorqueSensor const *)arg1)->getWrenchAppliedOnLinkInverseMatrix(arg2,*arg3); + arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); + result = (bool)iDynTree::ForwardAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::FreeFloatingAcc const &)*arg5,(iDynTree::LinkVelArray const &)*arg6,*arg7); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68274,45 +71684,92 @@ int _wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix(int resc, } -int _wrap_SixAxisForceTorqueSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; +int _wrap_ForwardBiasAccKinematics__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; iDynTree::Traversal *arg2 = 0 ; - iDynTree::LinkInternalWrenches *arg3 = 0 ; - void *argp1 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::SpatialAcc *arg5 = 0 ; + iDynTree::LinkVelArray *arg6 = 0 ; + iDynTree::LinkAccArray *arg7 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; void *argp3 ; int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; mxArray * _out; - iDynTree::Wrench result; + bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_predictMeasurement",argc,3,3,0)) { + if (!SWIG_check_num_args("ForwardBiasAccKinematics",argc,7,7,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::LinkInternalWrenches const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); } - arg3 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp3); - result = (arg1)->predictMeasurement((iDynTree::Traversal const &)*arg2,(iDynTree::LinkInternalWrenches const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::Wrench(static_cast< const iDynTree::Wrench& >(result))), SWIGTYPE_p_iDynTree__Wrench, SWIG_POINTER_OWN | 0 ); + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::SpatialAcc const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::SpatialAcc const &""'"); + } + arg5 = reinterpret_cast< iDynTree::SpatialAcc * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkVelArray * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ForwardBiasAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "7"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkAccArray * >(argp7); + result = (bool)iDynTree::ForwardBiasAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::SpatialAcc const &)*arg5,(iDynTree::LinkVelArray const &)*arg6,*arg7); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68320,34 +71777,81 @@ int _wrap_SixAxisForceTorqueSensor_predictMeasurement(int resc, mxArray *resv[], } -int _wrap_SixAxisForceTorqueSensor_toString(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::SixAxisForceTorqueSensor *arg1 = (iDynTree::SixAxisForceTorqueSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_ForwardBiasAccKinematics__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::LinkVelArray *arg5 = 0 ; + iDynTree::LinkAccArray *arg6 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; mxArray * _out; - std::string result; + bool result; - if (!SWIG_check_num_args("SixAxisForceTorqueSensor_toString",argc,2,2,0)) { + if (!SWIG_check_num_args("ForwardBiasAccKinematics",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__SixAxisForceTorqueSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "1"" of type '" "iDynTree::SixAxisForceTorqueSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::SixAxisForceTorqueSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "SixAxisForceTorqueSensor_toString" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = ((iDynTree::SixAxisForceTorqueSensor const *)arg1)->toString((iDynTree::Model const &)*arg2); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "5"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkVelArray * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ForwardBiasAccKinematics" "', argument " "6"" of type '" "iDynTree::LinkAccArray &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkAccArray * >(argp6); + result = (bool)iDynTree::ForwardBiasAccKinematics((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::LinkVelArray const &)*arg5,*arg6); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68355,43 +71859,142 @@ int _wrap_SixAxisForceTorqueSensor_toString(int resc, mxArray *resv[], int argc, } -int _wrap_new_AccelerometerSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - mxArray * _out; - iDynTree::AccelerometerSensor *result = 0 ; - - if (!SWIG_check_num_args("new_AccelerometerSensor",argc,0,0,0)) { - SWIG_fail; +int _wrap_ForwardBiasAccKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 6) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ForwardBiasAccKinematics__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + } } - (void)argv; - result = (iDynTree::AccelerometerSensor *)new iDynTree::AccelerometerSensor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 1 | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + if (argc == 7) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Traversal, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[4], &vptr, SWIGTYPE_p_iDynTree__SpatialAcc, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[5], &vptr, SWIGTYPE_p_iDynTree__LinkVelArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[6], &vptr, SWIGTYPE_p_iDynTree__LinkAccArray, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ForwardBiasAccKinematics__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ForwardBiasAccKinematics'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ForwardBiasAccKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::SpatialAcc const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray &)\n" + " iDynTree::ForwardBiasAccKinematics(iDynTree::Model const &,iDynTree::Traversal const &,iDynTree::FreeFloatingPos const &,iDynTree::FreeFloatingVel const &,iDynTree::LinkVelArray const &,iDynTree::LinkAccArray &)\n"); return 1; } -int _wrap_new_AccelerometerSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = 0 ; +int _wrap_ComputeLinearAndAngularMomentum(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::LinkPositions *arg2 = 0 ; + iDynTree::LinkVelArray *arg3 = 0 ; + iDynTree::SpatialMomentum *arg4 = 0 ; void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; mxArray * _out; - iDynTree::AccelerometerSensor *result = 0 ; + bool result; - if (!SWIG_check_num_args("new_AccelerometerSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ComputeLinearAndAngularMomentum",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = (iDynTree::AccelerometerSensor *)new iDynTree::AccelerometerSensor((iDynTree::AccelerometerSensor const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__AccelerometerSensor, 1 | 0 ); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkPositions * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::LinkVelArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__SpatialMomentum, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ComputeLinearAndAngularMomentum" "', argument " "4"" of type '" "iDynTree::SpatialMomentum &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentum" "', argument " "4"" of type '" "iDynTree::SpatialMomentum &""'"); + } + arg4 = reinterpret_cast< iDynTree::SpatialMomentum * >(argp4); + result = (bool)iDynTree::ComputeLinearAndAngularMomentum((iDynTree::Model const &)*arg1,(iDynTree::LinkPositions const &)*arg2,(iDynTree::LinkVelArray const &)*arg3,*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68399,48 +72002,70 @@ int _wrap_new_AccelerometerSensor__SWIG_1(int resc, mxArray *resv[], int argc, m } -int _wrap_new_AccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_AccelerometerSensor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__AccelerometerSensor, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_AccelerometerSensor__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_AccelerometerSensor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::AccelerometerSensor::AccelerometerSensor()\n" - " iDynTree::AccelerometerSensor::AccelerometerSensor(iDynTree::AccelerometerSensor const &)\n"); - return 1; -} - - -int _wrap_delete_AccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_ComputeLinearAndAngularMomentumDerivativeBias(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::LinkPositions *arg2 = 0 ; + iDynTree::LinkVelArray *arg3 = 0 ; + iDynTree::LinkAccArray *arg4 = 0 ; + iDynTree::Wrench *arg5 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_AccelerometerSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ComputeLinearAndAngularMomentumDerivativeBias",argc,5,5,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_AccelerometerSensor" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "2"" of type '" "iDynTree::LinkPositions const &""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkPositions * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "3"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::LinkVelArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "4"" of type '" "iDynTree::LinkAccArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkAccArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__Wrench, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "5"" of type '" "iDynTree::Wrench &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ComputeLinearAndAngularMomentumDerivativeBias" "', argument " "5"" of type '" "iDynTree::Wrench &""'"); + } + arg5 = reinterpret_cast< iDynTree::Wrench * >(argp5); + result = (bool)iDynTree::ComputeLinearAndAngularMomentumDerivativeBias((iDynTree::Model const &)*arg1,(iDynTree::LinkPositions const &)*arg2,(iDynTree::LinkVelArray const &)*arg3,(iDynTree::LinkAccArray const &)*arg4,*arg5); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68448,145 +72073,173 @@ int _wrap_delete_AccelerometerSensor(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_AccelerometerSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_RNEADynamicPhase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::JointPosDoubleArray *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::LinkAccArray *arg5 = 0 ; + iDynTree::LinkNetExternalWrenches *arg6 = 0 ; + iDynTree::LinkInternalWrenches *arg7 = 0 ; + iDynTree::FreeFloatingGeneralizedTorques *arg8 = 0 ; + void *argp1 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; + void *argp8 = 0 ; + int res8 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("AccelerometerSensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("RNEADynamicPhase",argc,8,8,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setName" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "RNEADynamicPhase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "RNEADynamicPhase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "RNEADynamicPhase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + } + arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "RNEADynamicPhase" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "RNEADynamicPhase" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "RNEADynamicPhase" "', argument " "6"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "6"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + arg6 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "RNEADynamicPhase" "', argument " "7"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "7"" of type '" "iDynTree::LinkInternalWrenches &""'"); + } + arg7 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp7); + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "RNEADynamicPhase" "', argument " "8"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); } - result = (bool)(arg1)->setName((std::string const &)*arg2); + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "RNEADynamicPhase" "', argument " "8"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); + } + arg8 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp8); + result = (bool)iDynTree::RNEADynamicPhase((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,(iDynTree::LinkWrenches const &)*arg6,*arg7,*arg8); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_AccelerometerSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - iDynTree::Transform *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_CompositeRigidBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::JointPosDoubleArray *arg3 = 0 ; + iDynTree::LinkCompositeRigidBodyInertias *arg4 = 0 ; + iDynTree::FreeFloatingMassMatrix *arg5 = 0 ; + void *argp1 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("AccelerometerSensor_setLinkSensorTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("CompositeRigidBodyAlgorithm",argc,5,5,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_AccelerometerSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("AccelerometerSensor_setParentLink",argc,2,2,0)) { - SWIG_fail; + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::JointPosDoubleArray const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg3 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkInertias, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::LinkCompositeRigidBodyInertias &""'"); } - result = (bool)(arg1)->setParentLink((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; - return 0; -fail: - if (SWIG_IsNewObj(res2)) delete arg2; - return 1; -} - - -int _wrap_AccelerometerSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - iDynTree::LinkIndex temp2 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("AccelerometerSensor_setParentLinkIndex",argc,2,2,0)) { - SWIG_fail; + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::LinkCompositeRigidBodyInertias &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + arg4 = reinterpret_cast< iDynTree::LinkCompositeRigidBodyInertias * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingMassMatrix, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "CompositeRigidBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::FreeFloatingMassMatrix &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "AccelerometerSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CompositeRigidBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::FreeFloatingMassMatrix &""'"); + } + arg5 = reinterpret_cast< iDynTree::FreeFloatingMassMatrix * >(argp5); + result = (bool)iDynTree::CompositeRigidBodyAlgorithm((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::JointPosDoubleArray const &)*arg3,*arg4,*arg5); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68595,23 +72248,16 @@ int _wrap_AccelerometerSensor_setParentLinkIndex(int resc, mxArray *resv[], int } -int _wrap_AccelerometerSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - std::string result; + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *result = 0 ; - if (!SWIG_check_num_args("AccelerometerSensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyAlgorithmInternalBuffers",argc,0,0,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getName" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = ((iDynTree::AccelerometerSensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + (void)argv; + result = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *)new iDynTree::ArticulatedBodyAlgorithmInternalBuffers(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68619,47 +72265,26 @@ int _wrap_AccelerometerSensor_getName(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_AccelerometerSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + void *argp1 ; int res1 = 0 ; mxArray * _out; - iDynTree::SensorType result; + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *result = 0 ; - if (!SWIG_check_num_args("AccelerometerSensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("new_ArticulatedBodyAlgorithmInternalBuffers",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::AccelerometerSensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_AccelerometerSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - std::string result; - - if (!SWIG_check_num_args("AccelerometerSensor_getParentLink",argc,1,1,0)) { - SWIG_fail; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = ((iDynTree::AccelerometerSensor const *)arg1)->getParentLink(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + result = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *)new iDynTree::ArticulatedBodyAlgorithmInternalBuffers((iDynTree::Model const &)*arg1); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68667,95 +72292,55 @@ int _wrap_AccelerometerSensor_getParentLink(int resc, mxArray *resv[], int argc, } -int _wrap_AccelerometerSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::LinkIndex result; - - if (!SWIG_check_num_args("AccelerometerSensor_getParentLinkIndex",argc,1,1,0)) { - SWIG_fail; +int _wrap_new_ArticulatedBodyAlgorithmInternalBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 0) { + return _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_0(resc,resv,argc,argv); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); + if (argc == 1) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_new_ArticulatedBodyAlgorithmInternalBuffers__SWIG_1(resc,resv,argc,argv); + } } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = ((iDynTree::AccelerometerSensor const *)arg1)->getParentLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_AccelerometerSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Transform result; - if (!SWIG_check_num_args("AccelerometerSensor_getLinkSensorTransform",argc,1,1,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = ((iDynTree::AccelerometerSensor const *)arg1)->getLinkSensorTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); - if (_out) --resc, *resv++ = _out; - return 0; -fail: + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ArticulatedBodyAlgorithmInternalBuffers'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ArticulatedBodyAlgorithmInternalBuffers::ArticulatedBodyAlgorithmInternalBuffers()\n" + " iDynTree::ArticulatedBodyAlgorithmInternalBuffers::ArticulatedBodyAlgorithmInternalBuffers(iDynTree::Model const &)\n"); return 1; } -int _wrap_AccelerometerSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_resize(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("AccelerometerSensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_resize",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_isValid" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = (bool)((iDynTree::AccelerometerSensor const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_AccelerometerSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - mxArray * _out; - iDynTree::Sensor *result = 0 ; - - if (!SWIG_check_num_args("AccelerometerSensor_clone",argc,1,1,0)) { - SWIG_fail; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_clone" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor const *""'"); + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithmInternalBuffers_resize" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::AccelerometerSensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + (arg1)->resize((iDynTree::Model const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68763,8 +72348,8 @@ int _wrap_AccelerometerSensor_clone(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_AccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_isConsistent(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; @@ -68773,23 +72358,23 @@ int _wrap_AccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray * _out; bool result; - if (!SWIG_check_num_args("AccelerometerSensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_isConsistent",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithmInternalBuffers_isConsistent" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + result = (bool)(arg1)->isConsistent((iDynTree::Model const &)*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -68798,45 +72383,30 @@ int _wrap_AccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, } -int _wrap_AccelerometerSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::AccelerometerSensor *arg1 = (iDynTree::AccelerometerSensor *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; - iDynTree::Twist *arg3 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::DOFSpatialMotionArray *arg2 = (iDynTree::DOFSpatialMotionArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; mxArray * _out; - iDynTree::LinAcceleration result; - if (!SWIG_check_num_args("AccelerometerSensor_predictMeasurement",argc,3,3,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_S_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__AccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::AccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::AccelerometerSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Twist, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "AccelerometerSensor_predictMeasurement" "', argument " "3"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_set" "', argument " "2"" of type '" "iDynTree::DOFSpatialMotionArray *""'"); } - arg3 = reinterpret_cast< iDynTree::Twist * >(argp3); - result = (arg1)->predictMeasurement((iDynTree::SpatialAcc const &)*arg2,(iDynTree::Twist const &)*arg3); - _out = SWIG_NewPointerObj((new iDynTree::LinAcceleration(static_cast< const iDynTree::LinAcceleration& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::DOFSpatialMotionArray * >(argp2); + if (arg1) (arg1)->S = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68844,16 +72414,23 @@ int _wrap_AccelerometerSensor_predictMeasurement(int resc, mxArray *resv[], int } -int _wrap_new_GyroscopeSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_S_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::GyroscopeSensor *result = 0 ; + iDynTree::DOFSpatialMotionArray *result = 0 ; - if (!SWIG_check_num_args("new_GyroscopeSensor",argc,0,0,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_S_get",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::GyroscopeSensor *)new iDynTree::GyroscopeSensor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_S_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + } + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::DOFSpatialMotionArray *)& ((arg1)->S); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialMotionArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68861,26 +72438,30 @@ int _wrap_new_GyroscopeSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_GyroscopeSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = 0 ; - void *argp1 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_U_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::DOFSpatialForceArray *arg2 = (iDynTree::DOFSpatialForceArray *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::GyroscopeSensor *result = 0 ; - if (!SWIG_check_num_args("new_GyroscopeSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_U_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const &""'"); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_set" "', argument " "2"" of type '" "iDynTree::DOFSpatialForceArray *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = (iDynTree::GyroscopeSensor *)new iDynTree::GyroscopeSensor((iDynTree::GyroscopeSensor const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__GyroscopeSensor, 1 | 0 ); + arg2 = reinterpret_cast< iDynTree::DOFSpatialForceArray * >(argp2); + if (arg1) (arg1)->U = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68888,48 +72469,23 @@ int _wrap_new_GyroscopeSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArr } -int _wrap_new_GyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_GyroscopeSensor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__GyroscopeSensor, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_GyroscopeSensor__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_GyroscopeSensor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::GyroscopeSensor::GyroscopeSensor()\n" - " iDynTree::GyroscopeSensor::GyroscopeSensor(iDynTree::GyroscopeSensor const &)\n"); - return 1; -} - - -int _wrap_delete_GyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_U_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; + iDynTree::DOFSpatialForceArray *result = 0 ; - int is_owned; - if (!SWIG_check_num_args("delete_GyroscopeSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_U_get",argc,1,1,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_GyroscopeSensor" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_U_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::DOFSpatialForceArray *)& ((arg1)->U); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DOFSpatialForceArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -68937,73 +72493,54 @@ int _wrap_delete_GyroscopeSensor(int resc, mxArray *resv[], int argc, mxArray *a } -int _wrap_GyroscopeSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_D_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::JointDOFsDoubleArray *arg2 = (iDynTree::JointDOFsDoubleArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("GyroscopeSensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_D_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setName" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_set" "', argument " "2"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); } - result = (bool)(arg1)->setName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp2); + if (arg1) (arg1)->D = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_GyroscopeSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_D_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_setLinkSensorTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_D_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_D_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + } + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *)& ((arg1)->D); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69011,72 +72548,54 @@ int _wrap_GyroscopeSensor_setLinkSensorTransform(int resc, mxArray *resv[], int } -int _wrap_GyroscopeSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_u_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::JointDOFsDoubleArray *arg2 = (iDynTree::JointDOFsDoubleArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("GyroscopeSensor_setParentLink",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_u_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_set" "', argument " "2"" of type '" "iDynTree::JointDOFsDoubleArray *""'"); } - result = (bool)(arg1)->setParentLink((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp2); + if (arg1) (arg1)->u = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_GyroscopeSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_u_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::LinkIndex temp2 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::JointDOFsDoubleArray *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_setParentLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_u_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_u_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "GyroscopeSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::JointDOFsDoubleArray *)& ((arg1)->u); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69084,23 +72603,30 @@ int _wrap_GyroscopeSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc } -int _wrap_GyroscopeSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::LinkVelArray *arg2 = (iDynTree::LinkVelArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("GyroscopeSensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksVel_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getName" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = ((iDynTree::GyroscopeSensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set" "', argument " "2"" of type '" "iDynTree::LinkVelArray *""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkVelArray * >(argp2); + if (arg1) (arg1)->linksVel = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69108,23 +72634,23 @@ int _wrap_GyroscopeSensor_getName(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_GyroscopeSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SensorType result; + iDynTree::LinkVelArray *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksVel_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksVel_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::GyroscopeSensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::LinkVelArray *)& ((arg1)->linksVel); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkVelArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69132,23 +72658,30 @@ int _wrap_GyroscopeSensor_getSensorType(int resc, mxArray *resv[], int argc, mxA } -int _wrap_GyroscopeSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::LinkAccArray *arg2 = (iDynTree::LinkAccArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("GyroscopeSensor_getParentLink",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = ((iDynTree::GyroscopeSensor const *)arg1)->getParentLink(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set" "', argument " "2"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkAccArray * >(argp2); + if (arg1) (arg1)->linksBiasAcceleration = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69156,23 +72689,23 @@ int _wrap_GyroscopeSensor_getParentLink(int resc, mxArray *resv[], int argc, mxA } -int _wrap_GyroscopeSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::LinkAccArray *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_getParentLinkIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = ((iDynTree::GyroscopeSensor const *)arg1)->getParentLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::LinkAccArray *)& ((arg1)->linksBiasAcceleration); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69180,23 +72713,30 @@ int _wrap_GyroscopeSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc } -int _wrap_GyroscopeSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::LinkAccArray *arg2 = (iDynTree::LinkAccArray *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Transform result; - if (!SWIG_check_num_args("GyroscopeSensor_getLinkSensorTransform",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = ((iDynTree::GyroscopeSensor const *)arg1)->getLinkSensorTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set" "', argument " "2"" of type '" "iDynTree::LinkAccArray *""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkAccArray * >(argp2); + if (arg1) (arg1)->linksAccelerations = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69204,23 +72744,23 @@ int _wrap_GyroscopeSensor_getLinkSensorTransform(int resc, mxArray *resv[], int } -int _wrap_GyroscopeSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - bool result; + iDynTree::LinkAccArray *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_isValid" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = (bool)((iDynTree::GyroscopeSensor const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::LinkAccArray *)& ((arg1)->linksAccelerations); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkAccArray, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69228,23 +72768,30 @@ int _wrap_GyroscopeSensor_isValid(int resc, mxArray *resv[], int argc, mxArray * } -int _wrap_GyroscopeSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::LinkArticulatedBodyInertias *arg2 = (iDynTree::LinkArticulatedBodyInertias *) 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_clone" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::GyroscopeSensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set" "', argument " "2"" of type '" "iDynTree::LinkArticulatedBodyInertias *""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkArticulatedBodyInertias * >(argp2); + if (arg1) (arg1)->linkABIs = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69252,34 +72799,23 @@ int _wrap_GyroscopeSensor_clone(int resc, mxArray *resv[], int argc, mxArray *ar } -int _wrap_GyroscopeSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - bool result; + iDynTree::LinkArticulatedBodyInertias *result = 0 ; - if (!SWIG_check_num_args("GyroscopeSensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::LinkArticulatedBodyInertias *)& ((arg1)->linkABIs); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkArticulatedBodyInertias, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69287,34 +72823,30 @@ int _wrap_GyroscopeSensor_updateIndices(int resc, mxArray *resv[], int argc, mxA } -int _wrap_GyroscopeSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::GyroscopeSensor *arg1 = (iDynTree::GyroscopeSensor *) 0 ; - iDynTree::Twist *arg2 = 0 ; +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + iDynTree::LinkWrenches *arg2 = (iDynTree::LinkWrenches *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; mxArray * _out; - iDynTree::AngVelocity result; - if (!SWIG_check_num_args("GyroscopeSensor_predictMeasurement",argc,2,2,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__GyroscopeSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::GyroscopeSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - arg1 = reinterpret_cast< iDynTree::GyroscopeSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Twist, 0 ); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "GyroscopeSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::Twist const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set" "', argument " "2"" of type '" "iDynTree::LinkWrenches *""'"); } - arg2 = reinterpret_cast< iDynTree::Twist * >(argp2); - result = (arg1)->predictMeasurement((iDynTree::Twist const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::AngVelocity(static_cast< const iDynTree::AngVelocity& >(result))), SWIGTYPE_p_iDynTree__GeomVector3, SWIG_POINTER_OWN | 0 ); + arg2 = reinterpret_cast< iDynTree::LinkWrenches * >(argp2); + if (arg1) (arg1)->linksBiasWrench = *arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69322,16 +72854,23 @@ int _wrap_GyroscopeSensor_predictMeasurement(int resc, mxArray *resv[], int argc } -int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; mxArray * _out; - iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; + iDynTree::LinkWrenches *result = 0 ; - if (!SWIG_check_num_args("new_ThreeAxisAngularAccelerometerSensor",argc,0,0,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get",argc,1,1,0)) { SWIG_fail; } - (void)argv; - result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)new iDynTree::ThreeAxisAngularAccelerometerSensor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 1 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); + } + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + result = (iDynTree::LinkWrenches *)& ((arg1)->linksBiasWrench); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__LinkWrenches, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69339,26 +72878,26 @@ int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_0(int resc, mxArray *res } -int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = 0 ; - void *argp1 ; +int _wrap_delete_ArticulatedBodyAlgorithmInternalBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg1 = (iDynTree::ArticulatedBodyAlgorithmInternalBuffers *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::ThreeAxisAngularAccelerometerSensor *result = 0 ; - if (!SWIG_check_num_args("new_ThreeAxisAngularAccelerometerSensor",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_ArticulatedBodyAlgorithmInternalBuffers",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ArticulatedBodyAlgorithmInternalBuffers" "', argument " "1"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const &""'"); + arg1 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = (iDynTree::ThreeAxisAngularAccelerometerSensor *)new iDynTree::ThreeAxisAngularAccelerometerSensor((iDynTree::ThreeAxisAngularAccelerometerSensor const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 1 | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69366,48 +72905,103 @@ int _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_1(int resc, mxArray *res } -int _wrap_new_ThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ThreeAxisAngularAccelerometerSensor__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ThreeAxisAngularAccelerometerSensor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ThreeAxisAngularAccelerometerSensor::ThreeAxisAngularAccelerometerSensor()\n" - " iDynTree::ThreeAxisAngularAccelerometerSensor::ThreeAxisAngularAccelerometerSensor(iDynTree::ThreeAxisAngularAccelerometerSensor const &)\n"); - return 1; -} - - -int _wrap_delete_ThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - void *argp1 = 0 ; +int _wrap_ArticulatedBodyAlgorithm(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::FreeFloatingPos *arg3 = 0 ; + iDynTree::FreeFloatingVel *arg4 = 0 ; + iDynTree::LinkNetExternalWrenches *arg5 = 0 ; + iDynTree::JointDOFsDoubleArray *arg6 = 0 ; + iDynTree::ArticulatedBodyAlgorithmInternalBuffers *arg7 = 0 ; + iDynTree::FreeFloatingAcc *arg8 = 0 ; + void *argp1 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 ; + int res6 = 0 ; + void *argp7 = 0 ; + int res7 = 0 ; + void *argp8 = 0 ; + int res8 = 0 ; mxArray * _out; + bool result; - int is_owned; - if (!SWIG_check_num_args("delete_ThreeAxisAngularAccelerometerSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("ArticulatedBodyAlgorithm",argc,8,8,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ThreeAxisAngularAccelerometerSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ArticulatedBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - if (is_owned) { - delete arg1; + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - _out = (mxArray*)0; + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ArticulatedBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ArticulatedBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "3"" of type '" "iDynTree::FreeFloatingPos const &""'"); + } + arg3 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ArticulatedBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "4"" of type '" "iDynTree::FreeFloatingVel const &""'"); + } + arg4 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ArticulatedBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "5"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); + } + arg5 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ArticulatedBodyAlgorithm" "', argument " "6"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "6"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + } + arg6 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp6); + res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__ArticulatedBodyAlgorithmInternalBuffers, 0 ); + if (!SWIG_IsOK(res7)) { + SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "ArticulatedBodyAlgorithm" "', argument " "7"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers &""'"); + } + if (!argp7) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "7"" of type '" "iDynTree::ArticulatedBodyAlgorithmInternalBuffers &""'"); + } + arg7 = reinterpret_cast< iDynTree::ArticulatedBodyAlgorithmInternalBuffers * >(argp7); + res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); + if (!SWIG_IsOK(res8)) { + SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "ArticulatedBodyAlgorithm" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + if (!argp8) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ArticulatedBodyAlgorithm" "', argument " "8"" of type '" "iDynTree::FreeFloatingAcc &""'"); + } + arg8 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp8); + result = (bool)iDynTree::ArticulatedBodyAlgorithm((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::FreeFloatingPos const &)*arg3,(iDynTree::FreeFloatingVel const &)*arg4,(iDynTree::LinkWrenches const &)*arg5,(iDynTree::JointDOFsDoubleArray const &)*arg6,*arg7,*arg8); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69415,73 +73009,112 @@ int _wrap_delete_ThreeAxisAngularAccelerometerSensor(int resc, mxArray *resv[], } -int _wrap_ThreeAxisAngularAccelerometerSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_InverseDynamicsInertialParametersRegressor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + iDynTree::Traversal *arg2 = 0 ; + iDynTree::LinkPositions *arg3 = 0 ; + iDynTree::LinkVelArray *arg4 = 0 ; + iDynTree::LinkAccArray *arg5 = 0 ; + iDynTree::MatrixDynSize *arg6 = 0 ; + void *argp1 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; + void *argp5 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("InverseDynamicsInertialParametersRegressor",argc,6,6,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Traversal, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "2"" of type '" "iDynTree::Traversal const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Traversal * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "3"" of type '" "iDynTree::LinkPositions const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "3"" of type '" "iDynTree::LinkPositions const &""'"); + } + arg3 = reinterpret_cast< iDynTree::LinkPositions * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); + } + arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__MatrixDynSize, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "6"" of type '" "iDynTree::MatrixDynSize &""'"); } - result = (bool)(arg1)->setName((std::string const &)*arg2); + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "InverseDynamicsInertialParametersRegressor" "', argument " "6"" of type '" "iDynTree::MatrixDynSize &""'"); + } + arg6 = reinterpret_cast< iDynTree::MatrixDynSize * >(argp6); + result = (bool)iDynTree::InverseDynamicsInertialParametersRegressor((iDynTree::Model const &)*arg1,(iDynTree::Traversal const &)*arg2,(iDynTree::LinkPositions const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,*arg6); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - iDynTree::Transform *arg2 = 0 ; +int _wrap_DHLink_A_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("DHLink_A_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_A_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_A_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->A = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69489,72 +73122,54 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform(int resc, m } -int _wrap_ThreeAxisAngularAccelerometerSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_DHLink_A_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setParentLink",argc,2,2,0)) { + if (!SWIG_check_num_args("DHLink_A_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_A_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - result = (bool)(arg1)->setParentLink((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->A); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ThreeAxisAngularAccelerometerSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_DHLink_D_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::LinkIndex temp2 ; - ptrdiff_t val2 ; + double val2 ; int ecode2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_setParentLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("DHLink_D_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_D_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_D_set" "', argument " "2"" of type '" "double""'"); } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->D = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69562,23 +73177,23 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_setParentLinkIndex(int resc, mxArr } -int _wrap_ThreeAxisAngularAccelerometerSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_D_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_D_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getName" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_D_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->D); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69586,23 +73201,30 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_getName(int resc, mxArray *resv[], } -int _wrap_ThreeAxisAngularAccelerometerSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Alpha_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::SensorType result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Alpha_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Alpha_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Alpha_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->Alpha = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69610,23 +73232,23 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_getSensorType(int resc, mxArray *r } -int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Alpha_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - std::string result; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getParentLink",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Alpha_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Alpha_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getParentLink(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->Alpha); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69634,23 +73256,30 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLink(int resc, mxArray *r } -int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Offset_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getParentLinkIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Offset_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Offset_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getParentLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Offset_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->Offset = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69658,23 +73287,23 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_getParentLinkIndex(int resc, mxArr } -int _wrap_ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Offset_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Transform result; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Offset_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Offset_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = ((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->getLinkSensorTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->Offset); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69682,23 +73311,30 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform(int resc, m } -int _wrap_ThreeAxisAngularAccelerometerSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Min_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Min_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_isValid" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Min_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = (bool)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Min_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->Min = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69706,23 +73342,23 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_isValid(int resc, mxArray *resv[], } -int _wrap_ThreeAxisAngularAccelerometerSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; +int _wrap_DHLink_Min_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("DHLink_Min_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_clone" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Min_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::ThreeAxisAngularAccelerometerSensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->Min); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69730,34 +73366,30 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_clone(int resc, mxArray *resv[], i } -int _wrap_ThreeAxisAngularAccelerometerSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - iDynTree::Model *arg2 = 0 ; +int _wrap_DHLink_Max_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + double arg2 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; + double val2 ; + int ecode2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("DHLink_Max_set",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Max_set" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHLink_Max_set" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + if (arg1) (arg1)->Max = arg2; + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69765,34 +73397,23 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_updateIndices(int resc, mxArray *r } -int _wrap_ThreeAxisAngularAccelerometerSensor_predictMeasurement(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisAngularAccelerometerSensor *arg1 = (iDynTree::ThreeAxisAngularAccelerometerSensor *) 0 ; - iDynTree::SpatialAcc *arg2 = 0 ; +int _wrap_DHLink_Max_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; mxArray * _out; - iDynTree::Vector3 result; + double result; - if (!SWIG_check_num_args("ThreeAxisAngularAccelerometerSensor_predictMeasurement",argc,2,2,0)) { + if (!SWIG_check_num_args("DHLink_Max_get",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisAngularAccelerometerSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "1"" of type '" "iDynTree::ThreeAxisAngularAccelerometerSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisAngularAccelerometerSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SpatialAcc, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisAngularAccelerometerSensor_predictMeasurement" "', argument " "2"" of type '" "iDynTree::SpatialAcc const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHLink_Max_get" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - arg2 = reinterpret_cast< iDynTree::SpatialAcc * >(argp2); - result = (arg1)->predictMeasurement((iDynTree::SpatialAcc const &)*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + result = (double) ((arg1)->Max); + _out = SWIG_From_double(static_cast< double >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69800,16 +73421,16 @@ int _wrap_ThreeAxisAngularAccelerometerSensor_predictMeasurement(int resc, mxArr } -int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_new_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; - iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; + iDynTree::DHLink *result = 0 ; - if (!SWIG_check_num_args("new_ThreeAxisForceTorqueContactSensor",argc,0,0,0)) { + if (!SWIG_check_num_args("new_DHLink",argc,0,0,0)) { SWIG_fail; } (void)argv; - result = (iDynTree::ThreeAxisForceTorqueContactSensor *)new iDynTree::ThreeAxisForceTorqueContactSensor(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 1 | 0 ); + result = (iDynTree::DHLink *)new iDynTree::DHLink(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 1 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69817,26 +73438,26 @@ int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_0(int resc, mxArray *resv[ } -int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = 0 ; - void *argp1 ; +int _wrap_delete_DHLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHLink *arg1 = (iDynTree::DHLink *) 0 ; + void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::ThreeAxisForceTorqueContactSensor *result = 0 ; - if (!SWIG_check_num_args("new_ThreeAxisForceTorqueContactSensor",argc,1,1,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_DHLink",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHLink, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "new_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DHLink" "', argument " "1"" of type '" "iDynTree::DHLink *""'"); } - if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "new_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const &""'"); + arg1 = reinterpret_cast< iDynTree::DHLink * >(argp1); + if (is_owned) { + delete arg1; } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = (iDynTree::ThreeAxisForceTorqueContactSensor *)new iDynTree::ThreeAxisForceTorqueContactSensor((iDynTree::ThreeAxisForceTorqueContactSensor const &)*arg1); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 1 | 0 ); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -69844,47 +73465,29 @@ int _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_1(int resc, mxArray *resv[ } -int _wrap_new_ThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - if (argc == 0) { - return _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_0(resc,resv,argc,argv); - } - if (argc == 1) { - int _v; - void *vptr = 0; - int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0); - _v = SWIG_CheckState(res); - if (_v) { - return _wrap_new_ThreeAxisForceTorqueContactSensor__SWIG_1(resc,resv,argc,argv); - } - } - - SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'new_ThreeAxisForceTorqueContactSensor'." - " Possible C/C++ prototypes are:\n" - " iDynTree::ThreeAxisForceTorqueContactSensor::ThreeAxisForceTorqueContactSensor()\n" - " iDynTree::ThreeAxisForceTorqueContactSensor::ThreeAxisForceTorqueContactSensor(iDynTree::ThreeAxisForceTorqueContactSensor const &)\n"); - return 1; -} - - -int _wrap_delete_ThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_setNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - int is_owned; - if (!SWIG_check_num_args("delete_ThreeAxisForceTorqueContactSensor",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_setNrOfDOFs",argc,2,2,0)) { SWIG_fail; } - is_owned = SWIG_Matlab_isOwned(argv[0]); - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, SWIG_POINTER_DISOWN | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_ThreeAxisForceTorqueContactSensor" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - if (is_owned) { - delete arg1; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setNrOfDOFs" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_setNrOfDOFs" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + (arg1)->setNrOfDOFs(arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -69893,146 +73496,81 @@ int _wrap_delete_ThreeAxisForceTorqueContactSensor(int resc, mxArray *resv[], in } -int _wrap_ThreeAxisForceTorqueContactSensor_setName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - std::string *arg2 = 0 ; +int _wrap_DHChain_getNrOfDOFs(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; mxArray * _out; - bool result; + size_t result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setName",argc,2,2,0)) { + if (!SWIG_check_num_args("DHChain_getNrOfDOFs",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setName" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getNrOfDOFs" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - result = (bool)(arg1)->setName((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + result = ((iDynTree::DHChain const *)arg1)->getNrOfDOFs(); + _out = SWIG_From_size_t(static_cast< size_t >(result)); if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ThreeAxisForceTorqueContactSensor_setLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_setH0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setLinkSensorTransform",argc,2,2,0)) { + if (!SWIG_check_num_args("DHChain_setH0",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setH0" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_setH0" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); - } - arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); - result = (bool)(arg1)->setLinkSensorTransform((iDynTree::Transform const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); - if (_out) --resc, *resv++ = _out; - return 0; -fail: - return 1; -} - - -int _wrap_ThreeAxisForceTorqueContactSensor_setParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - std::string *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - int res2 = SWIG_OLDOBJ ; - mxArray * _out; - bool result; - - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setParentLink",argc,2,2,0)) { - SWIG_fail; - } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - { - std::string *ptr = (std::string *)0; - res2 = SWIG_AsPtr_std_string(argv[1], &ptr); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - if (!ptr) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setParentLink" "', argument " "2"" of type '" "std::string const &""'"); - } - arg2 = ptr; + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setH0" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); } - result = (bool)(arg1)->setParentLink((std::string const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + (arg1)->setH0((iDynTree::Transform const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; - if (SWIG_IsNewObj(res2)) delete arg2; return 0; fail: - if (SWIG_IsNewObj(res2)) delete arg2; return 1; } -int _wrap_ThreeAxisForceTorqueContactSensor_setParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - iDynTree::LinkIndex *arg2 = 0 ; +int _wrap_DHChain_getH0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - iDynTree::LinkIndex temp2 ; - ptrdiff_t val2 ; - int ecode2 = 0 ; mxArray * _out; - bool result; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setParentLinkIndex",argc,2,2,0)) { + if (!SWIG_check_num_args("DHChain_getH0",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getH0" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - ecode2 = SWIG_AsVal_ptrdiff_t(argv[1], &val2); - if (!SWIG_IsOK(ecode2)) { - SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "ThreeAxisForceTorqueContactSensor_setParentLinkIndex" "', argument " "2"" of type '" "iDynTree::LinkIndex""'"); - } - temp2 = static_cast< iDynTree::LinkIndex >(val2); - arg2 = &temp2; - result = (bool)(arg1)->setParentLinkIndex((iDynTree::LinkIndex const &)*arg2); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + result = (iDynTree::Transform *) &((iDynTree::DHChain const *)arg1)->getH0(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70040,23 +73578,33 @@ int _wrap_ThreeAxisForceTorqueContactSensor_setParentLinkIndex(int resc, mxArray } -int _wrap_ThreeAxisForceTorqueContactSensor_getName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_setHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + iDynTree::Transform *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; mxArray * _out; - std::string result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getName",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_setHN",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getName" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setHN" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getName(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Transform, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_setHN" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setHN" "', argument " "2"" of type '" "iDynTree::Transform const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Transform * >(argp2); + (arg1)->setHN((iDynTree::Transform const &)*arg2); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70064,23 +73612,23 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getName(int resc, mxArray *resv[], i } -int _wrap_ThreeAxisForceTorqueContactSensor_getSensorType(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_getHN(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; void *argp1 = 0 ; int res1 = 0 ; mxArray * _out; - iDynTree::SensorType result; + iDynTree::Transform *result = 0 ; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getSensorType",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_getHN",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getSensorType" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getHN" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = (iDynTree::SensorType)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getSensorType(); - _out = SWIG_From_int(static_cast< int >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + result = (iDynTree::Transform *) &((iDynTree::DHChain const *)arg1)->getHN(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Transform, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70088,23 +73636,31 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getSensorType(int resc, mxArray *res } -int _wrap_ThreeAxisForceTorqueContactSensor_getParentLink(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_paren__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - std::string result; + iDynTree::DHLink *result = 0 ; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getParentLink",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getParentLink" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_paren" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getParentLink(); - _out = SWIG_From_std_string(static_cast< std::string >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::DHLink *) &(arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70112,23 +73668,31 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getParentLink(int resc, mxArray *res } -int _wrap_ThreeAxisForceTorqueContactSensor_getParentLinkIndex(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_paren__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::LinkIndex result; + iDynTree::DHLink *result = 0 ; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getParentLinkIndex",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_paren",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getParentLinkIndex" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_paren" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getParentLinkIndex(); - _out = SWIG_From_ptrdiff_t(static_cast< ptrdiff_t >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_paren" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = (iDynTree::DHLink *) &((iDynTree::DHChain const *)arg1)->operator ()(arg2); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHLink, 0 | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70136,23 +73700,71 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getParentLinkIndex(int resc, mxArray } -int _wrap_ThreeAxisForceTorqueContactSensor_getLinkSensorTransform(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_paren(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DHChain_paren__SWIG_0(resc,resv,argc,argv); + } + } + } + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_size_t(argv[1], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_DHChain_paren__SWIG_1(resc,resv,argc,argv); + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'DHChain_paren'." + " Possible C/C++ prototypes are:\n" + " iDynTree::DHChain::operator ()(size_t const)\n" + " iDynTree::DHChain::operator ()(size_t const) const\n"); + return 1; +} + + +int _wrap_DHChain_getDOFName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + size_t arg2 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; mxArray * _out; - iDynTree::Transform result; + std::string result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getLinkSensorTransform",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_getDOFName",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getLinkSensorTransform" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_getDOFName" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getLinkSensorTransform(); - _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_getDOFName" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + result = ((iDynTree::DHChain const *)arg1)->getDOFName(arg2); + _out = SWIG_From_std_string(static_cast< std::string >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70160,47 +73772,80 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getLinkSensorTransform(int resc, mxA } -int _wrap_ThreeAxisForceTorqueContactSensor_isValid(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_setDOFName(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + size_t arg2 ; + std::string *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + size_t val2 ; + int ecode2 = 0 ; + int res3 = SWIG_OLDOBJ ; mxArray * _out; - bool result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_isValid",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_setDOFName",argc,3,3,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_isValid" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_setDOFName" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = (bool)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->isValid(); - _out = SWIG_From_bool(static_cast< bool >(result)); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + ecode2 = SWIG_AsVal_size_t(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "DHChain_setDOFName" "', argument " "2"" of type '" "size_t""'"); + } + arg2 = static_cast< size_t >(val2); + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "DHChain_setDOFName" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_setDOFName" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; + } + (arg1)->setDOFName(arg2,(std::string const &)*arg3); + _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; return 0; fail: + if (SWIG_IsNewObj(res3)) delete arg3; return 1; } -int _wrap_ThreeAxisForceTorqueContactSensor_clone(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_toModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 = 0 ; int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; mxArray * _out; - iDynTree::Sensor *result = 0 ; + bool result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_clone",argc,1,1,0)) { + if (!SWIG_check_num_args("DHChain_toModel",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_clone" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_toModel" "', argument " "1"" of type '" "iDynTree::DHChain const *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = (iDynTree::Sensor *)((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->clone(); - _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__Sensor, 0 | 0 ); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_toModel" "', argument " "2"" of type '" "iDynTree::Model &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_toModel" "', argument " "2"" of type '" "iDynTree::Model &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)((iDynTree::DHChain const *)arg1)->toModel(*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70208,9 +73853,11 @@ int _wrap_ThreeAxisForceTorqueContactSensor_clone(int resc, mxArray *resv[], int } -int _wrap_ThreeAxisForceTorqueContactSensor_updateIndices(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; +int _wrap_DHChain_fromModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; iDynTree::Model *arg2 = 0 ; + std::string arg3 ; + std::string arg4 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; @@ -70218,23 +73865,41 @@ int _wrap_ThreeAxisForceTorqueContactSensor_updateIndices(int resc, mxArray *res mxArray * _out; bool result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_updateIndices",argc,2,2,0)) { + if (!SWIG_check_num_args("DHChain_fromModel",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, 0 | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "DHChain_fromModel" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "DHChain_fromModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_updateIndices" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "DHChain_fromModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->updateIndices((iDynTree::Model const &)*arg2); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "DHChain_fromModel" "', argument " "3"" of type '" "std::string""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[3], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "DHChain_fromModel" "', argument " "4"" of type '" "std::string""'"); + } + arg4 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + result = (bool)(arg1)->fromModel((iDynTree::Model const &)*arg2,arg3,arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -70243,32 +73908,42 @@ int _wrap_ThreeAxisForceTorqueContactSensor_updateIndices(int resc, mxArray *res } -int _wrap_ThreeAxisForceTorqueContactSensor_setLoadCellLocations(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > *arg2 = 0 ; +int _wrap_new_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + mxArray * _out; + iDynTree::DHChain *result = 0 ; + + if (!SWIG_check_num_args("new_DHChain",argc,0,0,0)) { + SWIG_fail; + } + (void)argv; + result = (iDynTree::DHChain *)new iDynTree::DHChain(); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_iDynTree__DHChain, 1 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_delete_DHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = (iDynTree::DHChain *) 0 ; void *argp1 = 0 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; mxArray * _out; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_setLoadCellLocations",argc,2,2,0)) { + int is_owned; + if (!SWIG_check_num_args("delete_DHChain",argc,1,1,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + is_owned = SWIG_Matlab_isOwned(argv[0]); + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__DHChain, SWIG_POINTER_DISOWN | 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "2"" of type '" "std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "delete_DHChain" "', argument " "1"" of type '" "iDynTree::DHChain *""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_setLoadCellLocations" "', argument " "2"" of type '" "std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > &""'"); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + if (is_owned) { + delete arg1; } - arg2 = reinterpret_cast< std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > * >(argp2); - (arg1)->setLoadCellLocations(*arg2); _out = (mxArray*)0; if (_out) --resc, *resv++ = _out; return 0; @@ -70277,23 +73952,47 @@ int _wrap_ThreeAxisForceTorqueContactSensor_setLoadCellLocations(int resc, mxArr } -int _wrap_ThreeAxisForceTorqueContactSensor_getLoadCellLocations(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - void *argp1 = 0 ; - int res1 = 0 ; +int _wrap_TransformFromDHCraig1989(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double arg4 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - SwigValueWrapper< std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > > result; + iDynTree::Transform result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_getLoadCellLocations",argc,1,1,0)) { + if (!SWIG_check_num_args("TransformFromDHCraig1989",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_getLoadCellLocations" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->getLoadCellLocations(); - _out = SWIG_NewPointerObj((new std::vector< iDynTree::Position,std::allocator< iDynTree::Position > >(static_cast< const std::vector< iDynTree::Position,std::allocator< iDynTree::Position > >& >(result))), SWIGTYPE_p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t, SWIG_POINTER_OWN | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "TransformFromDHCraig1989" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "TransformFromDHCraig1989" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "TransformFromDHCraig1989" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "TransformFromDHCraig1989" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = iDynTree::TransformFromDHCraig1989(arg1,arg2,arg3,arg4); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70301,34 +74000,47 @@ int _wrap_ThreeAxisForceTorqueContactSensor_getLoadCellLocations(int resc, mxArr } -int _wrap_ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - void *argp1 = 0 ; - int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; +int _wrap_TransformFromDH(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + double arg1 ; + double arg2 ; + double arg3 ; + double arg4 ; + double val1 ; + int ecode1 = 0 ; + double val2 ; + int ecode2 = 0 ; + double val3 ; + int ecode3 = 0 ; + double val4 ; + int ecode4 = 0 ; mxArray * _out; - iDynTree::Vector3 result; + iDynTree::Transform result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements",argc,2,2,0)) { + if (!SWIG_check_num_args("TransformFromDH",argc,4,4,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); - if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); - } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); - } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->computeThreeAxisForceTorqueFromLoadCellMeasurements(*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Vector3(static_cast< const iDynTree::Vector3& >(result))), SWIGTYPE_p_iDynTree__VectorFixSizeT_3_t, SWIG_POINTER_OWN | 0 ); + ecode1 = SWIG_AsVal_double(argv[0], &val1); + if (!SWIG_IsOK(ecode1)) { + SWIG_exception_fail(SWIG_ArgError(ecode1), "in method '" "TransformFromDH" "', argument " "1"" of type '" "double""'"); + } + arg1 = static_cast< double >(val1); + ecode2 = SWIG_AsVal_double(argv[1], &val2); + if (!SWIG_IsOK(ecode2)) { + SWIG_exception_fail(SWIG_ArgError(ecode2), "in method '" "TransformFromDH" "', argument " "2"" of type '" "double""'"); + } + arg2 = static_cast< double >(val2); + ecode3 = SWIG_AsVal_double(argv[2], &val3); + if (!SWIG_IsOK(ecode3)) { + SWIG_exception_fail(SWIG_ArgError(ecode3), "in method '" "TransformFromDH" "', argument " "3"" of type '" "double""'"); + } + arg3 = static_cast< double >(val3); + ecode4 = SWIG_AsVal_double(argv[3], &val4); + if (!SWIG_IsOK(ecode4)) { + SWIG_exception_fail(SWIG_ArgError(ecode4), "in method '" "TransformFromDH" "', argument " "4"" of type '" "double""'"); + } + arg4 = static_cast< double >(val4); + result = iDynTree::TransformFromDH(arg1,arg2,arg3,arg4); + _out = SWIG_NewPointerObj((new iDynTree::Transform(static_cast< const iDynTree::Transform& >(result))), SWIGTYPE_p_iDynTree__Transform, SWIG_POINTER_OWN | 0 ); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70336,34 +74048,65 @@ int _wrap_ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadC } -int _wrap_ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::ThreeAxisForceTorqueContactSensor *arg1 = (iDynTree::ThreeAxisForceTorqueContactSensor *) 0 ; - iDynTree::VectorDynSize *arg2 = 0 ; - void *argp1 = 0 ; +int _wrap_ExtractDHChainFromModel__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::Model *arg1 = 0 ; + std::string arg2 ; + std::string arg3 ; + iDynTree::DHChain *arg4 = 0 ; + double arg5 ; + void *argp1 ; int res1 = 0 ; - void *argp2 = 0 ; - int res2 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + double val5 ; + int ecode5 = 0 ; mxArray * _out; - iDynTree::Position result; + bool result; - if (!SWIG_check_num_args("ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements",argc,2,2,0)) { + if (!SWIG_check_num_args("ExtractDHChainFromModel",argc,5,5,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ThreeAxisForceTorqueContactSensor, 0 | 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "1"" of type '" "iDynTree::ThreeAxisForceTorqueContactSensor const *""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } - arg1 = reinterpret_cast< iDynTree::ThreeAxisForceTorqueContactSensor * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + if (!argp1) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + } + arg1 = reinterpret_cast< iDynTree::Model * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "3"" of type '" "std::string const""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__DHChain, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements" "', argument " "2"" of type '" "iDynTree::VectorDynSize &""'"); + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); } - arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); - result = ((iDynTree::ThreeAxisForceTorqueContactSensor const *)arg1)->computeCenterOfPressureFromLoadCellMeasurements(*arg2); - _out = SWIG_NewPointerObj((new iDynTree::Position(static_cast< const iDynTree::Position& >(result))), SWIGTYPE_p_iDynTree__Position, SWIG_POINTER_OWN | 0 ); + arg4 = reinterpret_cast< iDynTree::DHChain * >(argp4); + ecode5 = SWIG_AsVal_double(argv[4], &val5); + if (!SWIG_IsOK(ecode5)) { + SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "ExtractDHChainFromModel" "', argument " "5"" of type '" "double""'"); + } + arg5 = static_cast< double >(val5); + result = (bool)iDynTree::ExtractDHChainFromModel((iDynTree::Model const &)*arg1,arg2,arg3,*arg4,arg5); + _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; fail: @@ -70371,179 +74114,56 @@ int _wrap_ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellM } -int _wrap_predictSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ExtractDHChainFromModel__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::Model *arg1 = 0 ; - iDynTree::SensorsList *arg2 = 0 ; - iDynTree::Traversal *arg3 = 0 ; - iDynTree::FreeFloatingPos *arg4 = 0 ; - iDynTree::FreeFloatingVel *arg5 = 0 ; - iDynTree::FreeFloatingAcc *arg6 = 0 ; - iDynTree::LinAcceleration *arg7 = 0 ; - iDynTree::LinkNetExternalWrenches *arg8 = 0 ; - iDynTree::FreeFloatingAcc *arg9 = 0 ; - iDynTree::LinkPositions *arg10 = 0 ; - iDynTree::LinkVelArray *arg11 = 0 ; - iDynTree::LinkAccArray *arg12 = 0 ; - iDynTree::LinkInternalWrenches *arg13 = 0 ; - iDynTree::FreeFloatingGeneralizedTorques *arg14 = 0 ; - iDynTree::SensorsMeasurements *arg15 = 0 ; + std::string arg2 ; + std::string arg3 ; + iDynTree::DHChain *arg4 = 0 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; - int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; + void *argp4 = 0 ; int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 ; - int res7 = 0 ; - void *argp8 ; - int res8 = 0 ; - void *argp9 = 0 ; - int res9 = 0 ; - void *argp10 = 0 ; - int res10 = 0 ; - void *argp11 = 0 ; - int res11 = 0 ; - void *argp12 = 0 ; - int res12 = 0 ; - void *argp13 = 0 ; - int res13 = 0 ; - void *argp14 = 0 ; - int res14 = 0 ; - void *argp15 = 0 ; - int res15 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("predictSensorsMeasurements",argc,15,15,0)) { + if (!SWIG_check_num_args("ExtractDHChainFromModel",argc,4,4,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "1"" of type '" "iDynTree::Model const &""'"); } arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); - if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); - } - if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ExtractDHChainFromModel" "', argument " "3"" of type '" "std::string const""'"); + } + arg3 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; } - arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__FreeFloatingPos, 0 ); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__DHChain, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingPos const &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "4"" of type '" "iDynTree::FreeFloatingPos const &""'"); - } - arg4 = reinterpret_cast< iDynTree::FreeFloatingPos * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__FreeFloatingVel, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "5"" of type '" "iDynTree::FreeFloatingVel const &""'"); - } - arg5 = reinterpret_cast< iDynTree::FreeFloatingVel * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "6"" of type '" "iDynTree::FreeFloatingAcc const &""'"); - } - arg6 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__GeomVector3, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinAcceleration const &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "7"" of type '" "iDynTree::LinAcceleration const &""'"); - } - arg7 = reinterpret_cast< iDynTree::LinAcceleration * >(argp7); - res8 = SWIG_ConvertPtr(argv[7], &argp8, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res8)) { - SWIG_exception_fail(SWIG_ArgError(res8), "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - if (!argp8) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "8"" of type '" "iDynTree::LinkNetExternalWrenches const &""'"); - } - arg8 = reinterpret_cast< iDynTree::LinkNetExternalWrenches * >(argp8); - res9 = SWIG_ConvertPtr(argv[8], &argp9, SWIGTYPE_p_iDynTree__FreeFloatingAcc, 0 ); - if (!SWIG_IsOK(res9)) { - SWIG_exception_fail(SWIG_ArgError(res9), "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::FreeFloatingAcc &""'"); - } - if (!argp9) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "9"" of type '" "iDynTree::FreeFloatingAcc &""'"); - } - arg9 = reinterpret_cast< iDynTree::FreeFloatingAcc * >(argp9); - res10 = SWIG_ConvertPtr(argv[9], &argp10, SWIGTYPE_p_iDynTree__LinkPositions, 0 ); - if (!SWIG_IsOK(res10)) { - SWIG_exception_fail(SWIG_ArgError(res10), "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkPositions &""'"); - } - if (!argp10) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "10"" of type '" "iDynTree::LinkPositions &""'"); - } - arg10 = reinterpret_cast< iDynTree::LinkPositions * >(argp10); - res11 = SWIG_ConvertPtr(argv[10], &argp11, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res11)) { - SWIG_exception_fail(SWIG_ArgError(res11), "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkVelArray &""'"); - } - if (!argp11) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "11"" of type '" "iDynTree::LinkVelArray &""'"); - } - arg11 = reinterpret_cast< iDynTree::LinkVelArray * >(argp11); - res12 = SWIG_ConvertPtr(argv[11], &argp12, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res12)) { - SWIG_exception_fail(SWIG_ArgError(res12), "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkAccArray &""'"); - } - if (!argp12) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "12"" of type '" "iDynTree::LinkAccArray &""'"); - } - arg12 = reinterpret_cast< iDynTree::LinkAccArray * >(argp12); - res13 = SWIG_ConvertPtr(argv[12], &argp13, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res13)) { - SWIG_exception_fail(SWIG_ArgError(res13), "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::LinkInternalWrenches &""'"); - } - if (!argp13) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "13"" of type '" "iDynTree::LinkInternalWrenches &""'"); - } - arg13 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp13); - res14 = SWIG_ConvertPtr(argv[13], &argp14, SWIGTYPE_p_iDynTree__FreeFloatingGeneralizedTorques, 0 ); - if (!SWIG_IsOK(res14)) { - SWIG_exception_fail(SWIG_ArgError(res14), "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); - } - if (!argp14) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "14"" of type '" "iDynTree::FreeFloatingGeneralizedTorques &""'"); - } - arg14 = reinterpret_cast< iDynTree::FreeFloatingGeneralizedTorques * >(argp14); - res15 = SWIG_ConvertPtr(argv[14], &argp15, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); - if (!SWIG_IsOK(res15)) { - SWIG_exception_fail(SWIG_ArgError(res15), "in method '" "predictSensorsMeasurements" "', argument " "15"" of type '" "iDynTree::SensorsMeasurements &""'"); - } - if (!argp15) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurements" "', argument " "15"" of type '" "iDynTree::SensorsMeasurements &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtractDHChainFromModel" "', argument " "4"" of type '" "iDynTree::DHChain &""'"); } - arg15 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp15); - result = (bool)iDynTree::predictSensorsMeasurements((iDynTree::Model const &)*arg1,(iDynTree::SensorsList const &)*arg2,(iDynTree::Traversal const &)*arg3,(iDynTree::FreeFloatingPos const &)*arg4,(iDynTree::FreeFloatingVel const &)*arg5,(iDynTree::FreeFloatingAcc const &)*arg6,(iDynTree::GeomVector3 const &)*arg7,(iDynTree::LinkWrenches const &)*arg8,*arg9,*arg10,*arg11,*arg12,*arg13,*arg14,*arg15); + arg4 = reinterpret_cast< iDynTree::DHChain * >(argp4); + result = (bool)iDynTree::ExtractDHChainFromModel((iDynTree::Model const &)*arg1,arg2,arg3,*arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -70552,91 +74172,96 @@ int _wrap_predictSensorsMeasurements(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_predictSensorsMeasurementsFromRawBuffers(int resc, mxArray *resv[], int argc, mxArray *argv[]) { - iDynTree::Model *arg1 = 0 ; - iDynTree::SensorsList *arg2 = 0 ; - iDynTree::Traversal *arg3 = 0 ; - iDynTree::LinkVelArray *arg4 = 0 ; - iDynTree::LinkAccArray *arg5 = 0 ; - iDynTree::LinkInternalWrenches *arg6 = 0 ; - iDynTree::SensorsMeasurements *arg7 = 0 ; +int _wrap_ExtractDHChainFromModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 4) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ExtractDHChainFromModel__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + if (argc == 5) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__DHChain, 0); + _v = SWIG_CheckState(res); + if (_v) { + { + int res = SWIG_AsVal_double(argv[4], NULL); + _v = SWIG_CheckState(res); + } + if (_v) { + return _wrap_ExtractDHChainFromModel__SWIG_0(resc,resv,argc,argv); + } + } + } + } + } + } + + SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ExtractDHChainFromModel'." + " Possible C/C++ prototypes are:\n" + " iDynTree::ExtractDHChainFromModel(iDynTree::Model const &,std::string const,std::string const,iDynTree::DHChain &,double)\n" + " iDynTree::ExtractDHChainFromModel(iDynTree::Model const &,std::string const,std::string const,iDynTree::DHChain &)\n"); + return 1; +} + + +int _wrap_CreateModelFromDHChain(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::DHChain *arg1 = 0 ; + iDynTree::Model *arg2 = 0 ; void *argp1 ; int res1 = 0 ; - void *argp2 ; + void *argp2 = 0 ; int res2 = 0 ; - void *argp3 ; - int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; - void *argp5 ; - int res5 = 0 ; - void *argp6 ; - int res6 = 0 ; - void *argp7 = 0 ; - int res7 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("predictSensorsMeasurementsFromRawBuffers",argc,7,7,0)) { + if (!SWIG_check_num_args("CreateModelFromDHChain",argc,2,2,0)) { SWIG_fail; } - res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__Model, 0 ); + res1 = SWIG_ConvertPtr(argv[0], &argp1, SWIGTYPE_p_iDynTree__DHChain, 0 ); if (!SWIG_IsOK(res1)) { - SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "CreateModelFromDHChain" "', argument " "1"" of type '" "iDynTree::DHChain const &""'"); } if (!argp1) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "1"" of type '" "iDynTree::Model const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CreateModelFromDHChain" "', argument " "1"" of type '" "iDynTree::DHChain const &""'"); } - arg1 = reinterpret_cast< iDynTree::Model * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__SensorsList, 0 ); + arg1 = reinterpret_cast< iDynTree::DHChain * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "CreateModelFromDHChain" "', argument " "2"" of type '" "iDynTree::Model &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "2"" of type '" "iDynTree::SensorsList const &""'"); - } - arg2 = reinterpret_cast< iDynTree::SensorsList * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__Traversal, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "3"" of type '" "iDynTree::Traversal const &""'"); - } - arg3 = reinterpret_cast< iDynTree::Traversal * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__LinkVelArray, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "4"" of type '" "iDynTree::LinkVelArray const &""'"); - } - arg4 = reinterpret_cast< iDynTree::LinkVelArray * >(argp4); - res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_iDynTree__LinkAccArray, 0 ); - if (!SWIG_IsOK(res5)) { - SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - if (!argp5) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "5"" of type '" "iDynTree::LinkAccArray const &""'"); - } - arg5 = reinterpret_cast< iDynTree::LinkAccArray * >(argp5); - res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_iDynTree__LinkWrenches, 0 ); - if (!SWIG_IsOK(res6)) { - SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::LinkInternalWrenches const &""'"); - } - if (!argp6) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "6"" of type '" "iDynTree::LinkInternalWrenches const &""'"); - } - arg6 = reinterpret_cast< iDynTree::LinkInternalWrenches * >(argp6); - res7 = SWIG_ConvertPtr(argv[6], &argp7, SWIGTYPE_p_iDynTree__SensorsMeasurements, 0 ); - if (!SWIG_IsOK(res7)) { - SWIG_exception_fail(SWIG_ArgError(res7), "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "7"" of type '" "iDynTree::SensorsMeasurements &""'"); - } - if (!argp7) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "predictSensorsMeasurementsFromRawBuffers" "', argument " "7"" of type '" "iDynTree::SensorsMeasurements &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "CreateModelFromDHChain" "', argument " "2"" of type '" "iDynTree::Model &""'"); } - arg7 = reinterpret_cast< iDynTree::SensorsMeasurements * >(argp7); - result = (bool)iDynTree::predictSensorsMeasurementsFromRawBuffers((iDynTree::Model const &)*arg1,(iDynTree::SensorsList const &)*arg2,(iDynTree::Traversal const &)*arg3,(iDynTree::LinkVelArray const &)*arg4,(iDynTree::LinkAccArray const &)*arg5,(iDynTree::LinkWrenches const &)*arg6,*arg7); + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)iDynTree::CreateModelFromDHChain((iDynTree::DHChain const &)*arg1,*arg2); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -70993,6 +74618,75 @@ int _wrap_ModelLoader_setParsingOptions(int resc, mxArray *resv[], int argc, mxA int _wrap_ModelLoader_loadModelFromString__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg4 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + int res4 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ModelLoader_loadModelFromString",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelLoader, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelLoader_loadModelFromString" "', argument " "1"" of type '" "iDynTree::ModelLoader *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelLoader * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ModelLoader_loadModelFromString" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromString" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelLoader_loadModelFromString" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromString" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res4 = swig::asptr(argv[3], &ptr); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ModelLoader_loadModelFromString" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromString" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg4 = ptr; + } + result = (bool)(arg1)->loadModelFromString((std::string const &)*arg2,(std::string const &)*arg3,(std::vector< std::string,std::allocator< std::string > > const &)*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; + return 1; +} + + +int _wrap_ModelLoader_loadModelFromString__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string *arg2 = 0 ; std::string *arg3 = 0 ; @@ -71046,7 +74740,7 @@ int _wrap_ModelLoader_loadModelFromString__SWIG_0(int resc, mxArray *resv[], int } -int _wrap_ModelLoader_loadModelFromString__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ModelLoader_loadModelFromString__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string *arg2 = 0 ; void *argp1 = 0 ; @@ -71095,7 +74789,7 @@ int _wrap_ModelLoader_loadModelFromString(int resc, mxArray *resv[], int argc, m int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadModelFromString__SWIG_1(resc,resv,argc,argv); + return _wrap_ModelLoader_loadModelFromString__SWIG_2(resc,resv,argc,argv); } } } @@ -71111,7 +74805,28 @@ int _wrap_ModelLoader_loadModelFromString(int resc, mxArray *resv[], int argc, m int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadModelFromString__SWIG_0(resc,resv,argc,argv); + return _wrap_ModelLoader_loadModelFromString__SWIG_1(resc,resv,argc,argv); + } + } + } + } + if (argc == 4) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ModelLoader, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[3], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ModelLoader_loadModelFromString__SWIG_0(resc,resv,argc,argv); + } } } } @@ -71119,6 +74834,7 @@ int _wrap_ModelLoader_loadModelFromString(int resc, mxArray *resv[], int argc, m SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ModelLoader_loadModelFromString'." " Possible C/C++ prototypes are:\n" + " iDynTree::ModelLoader::loadModelFromString(std::string const &,std::string const &,std::vector< std::string,std::allocator< std::string > > const &)\n" " iDynTree::ModelLoader::loadModelFromString(std::string const &,std::string const &)\n" " iDynTree::ModelLoader::loadModelFromString(std::string const &)\n"); return 1; @@ -71126,6 +74842,75 @@ int _wrap_ModelLoader_loadModelFromString(int resc, mxArray *resv[], int argc, m int _wrap_ModelLoader_loadModelFromFile__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; + std::string *arg2 = 0 ; + std::string *arg3 = 0 ; + std::vector< std::string,std::allocator< std::string > > *arg4 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res2 = SWIG_OLDOBJ ; + int res3 = SWIG_OLDOBJ ; + int res4 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ModelLoader_loadModelFromFile",argc,4,4,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelLoader, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelLoader_loadModelFromFile" "', argument " "1"" of type '" "iDynTree::ModelLoader *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelLoader * >(argp1); + { + std::string *ptr = (std::string *)0; + res2 = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ModelLoader_loadModelFromFile" "', argument " "2"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromFile" "', argument " "2"" of type '" "std::string const &""'"); + } + arg2 = ptr; + } + { + std::string *ptr = (std::string *)0; + res3 = SWIG_AsPtr_std_string(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelLoader_loadModelFromFile" "', argument " "3"" of type '" "std::string const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromFile" "', argument " "3"" of type '" "std::string const &""'"); + } + arg3 = ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res4 = swig::asptr(argv[3], &ptr); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ModelLoader_loadModelFromFile" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadModelFromFile" "', argument " "4"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg4 = ptr; + } + result = (bool)(arg1)->loadModelFromFile((std::string const &)*arg2,(std::string const &)*arg3,(std::vector< std::string,std::allocator< std::string > > const &)*arg4); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; + return 0; +fail: + if (SWIG_IsNewObj(res2)) delete arg2; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res4)) delete arg4; + return 1; +} + + +int _wrap_ModelLoader_loadModelFromFile__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string *arg2 = 0 ; std::string *arg3 = 0 ; @@ -71179,7 +74964,7 @@ int _wrap_ModelLoader_loadModelFromFile__SWIG_0(int resc, mxArray *resv[], int a } -int _wrap_ModelLoader_loadModelFromFile__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ModelLoader_loadModelFromFile__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string *arg2 = 0 ; void *argp1 = 0 ; @@ -71228,7 +75013,7 @@ int _wrap_ModelLoader_loadModelFromFile(int resc, mxArray *resv[], int argc, mxA int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadModelFromFile__SWIG_1(resc,resv,argc,argv); + return _wrap_ModelLoader_loadModelFromFile__SWIG_2(resc,resv,argc,argv); } } } @@ -71244,7 +75029,28 @@ int _wrap_ModelLoader_loadModelFromFile(int resc, mxArray *resv[], int argc, mxA int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadModelFromFile__SWIG_0(resc,resv,argc,argv); + return _wrap_ModelLoader_loadModelFromFile__SWIG_1(resc,resv,argc,argv); + } + } + } + } + if (argc == 4) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ModelLoader, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[2], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[3], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ModelLoader_loadModelFromFile__SWIG_0(resc,resv,argc,argv); + } } } } @@ -71252,6 +75058,7 @@ int _wrap_ModelLoader_loadModelFromFile(int resc, mxArray *resv[], int argc, mxA SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ModelLoader_loadModelFromFile'." " Possible C/C++ prototypes are:\n" + " iDynTree::ModelLoader::loadModelFromFile(std::string const &,std::string const &,std::vector< std::string,std::allocator< std::string > > const &)\n" " iDynTree::ModelLoader::loadModelFromFile(std::string const &,std::string const &)\n" " iDynTree::ModelLoader::loadModelFromFile(std::string const &)\n"); return 1; @@ -71419,6 +75226,80 @@ int _wrap_ModelLoader_loadReducedModelFromFullModel(int resc, mxArray *resv[], i int _wrap_ModelLoader_loadReducedModelFromString__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; + std::string arg2 ; + std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; + std::string arg4 ; + std::vector< std::string,std::allocator< std::string > > *arg5 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res3 = SWIG_OLDOBJ ; + int res5 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ModelLoader_loadReducedModelFromString",argc,5,5,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelLoader, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "1"" of type '" "iDynTree::ModelLoader *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelLoader * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg3 = ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[3], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "4"" of type '" "std::string const""'"); + } + arg4 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res5 = swig::asptr(argv[4], &ptr); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "5"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadReducedModelFromString" "', argument " "5"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg5 = ptr; + } + result = (bool)(arg1)->loadReducedModelFromString(arg2,(std::vector< std::string,std::allocator< std::string > > const &)*arg3,arg4,(std::vector< std::string,std::allocator< std::string > > const &)*arg5); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + return 0; +fail: + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + return 1; +} + + +int _wrap_ModelLoader_loadReducedModelFromString__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string arg2 ; std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; @@ -71477,7 +75358,7 @@ int _wrap_ModelLoader_loadReducedModelFromString__SWIG_0(int resc, mxArray *resv } -int _wrap_ModelLoader_loadReducedModelFromString__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ModelLoader_loadReducedModelFromString__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string arg2 ; std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; @@ -71539,7 +75420,7 @@ int _wrap_ModelLoader_loadReducedModelFromString(int resc, mxArray *resv[], int int res = swig::asptr(argv[2], (std::vector< std::string,std::allocator< std::string > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadReducedModelFromString__SWIG_1(resc,resv,argc,argv); + return _wrap_ModelLoader_loadReducedModelFromString__SWIG_2(resc,resv,argc,argv); } } } @@ -71559,7 +75440,32 @@ int _wrap_ModelLoader_loadReducedModelFromString(int resc, mxArray *resv[], int int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadReducedModelFromString__SWIG_0(resc,resv,argc,argv); + return _wrap_ModelLoader_loadReducedModelFromString__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + if (argc == 5) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ModelLoader, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[2], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[4], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ModelLoader_loadReducedModelFromString__SWIG_0(resc,resv,argc,argv); + } } } } @@ -71568,6 +75474,7 @@ int _wrap_ModelLoader_loadReducedModelFromString(int resc, mxArray *resv[], int SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ModelLoader_loadReducedModelFromString'." " Possible C/C++ prototypes are:\n" + " iDynTree::ModelLoader::loadReducedModelFromString(std::string const,std::vector< std::string,std::allocator< std::string > > const &,std::string const,std::vector< std::string,std::allocator< std::string > > const &)\n" " iDynTree::ModelLoader::loadReducedModelFromString(std::string const,std::vector< std::string,std::allocator< std::string > > const &,std::string const)\n" " iDynTree::ModelLoader::loadReducedModelFromString(std::string const,std::vector< std::string,std::allocator< std::string > > const &)\n"); return 1; @@ -71575,6 +75482,80 @@ int _wrap_ModelLoader_loadReducedModelFromString(int resc, mxArray *resv[], int int _wrap_ModelLoader_loadReducedModelFromFile__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; + std::string arg2 ; + std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; + std::string arg4 ; + std::vector< std::string,std::allocator< std::string > > *arg5 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + int res3 = SWIG_OLDOBJ ; + int res5 = SWIG_OLDOBJ ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ModelLoader_loadReducedModelFromFile",argc,5,5,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelLoader, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "1"" of type '" "iDynTree::ModelLoader *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelLoader * >(argp1); + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[1], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "2"" of type '" "std::string const""'"); + } + arg2 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res3 = swig::asptr(argv[2], &ptr); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "3"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg3 = ptr; + } + { + std::string *ptr = (std::string *)0; + int res = SWIG_AsPtr_std_string(argv[3], &ptr); + if (!SWIG_IsOK(res) || !ptr) { + SWIG_exception_fail(SWIG_ArgError((ptr ? res : SWIG_TypeError)), "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "4"" of type '" "std::string const""'"); + } + arg4 = *ptr; + if (SWIG_IsNewObj(res)) delete ptr; + } + { + std::vector< std::string,std::allocator< std::string > > *ptr = (std::vector< std::string,std::allocator< std::string > > *)0; + res5 = swig::asptr(argv[4], &ptr); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "5"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + if (!ptr) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelLoader_loadReducedModelFromFile" "', argument " "5"" of type '" "std::vector< std::string,std::allocator< std::string > > const &""'"); + } + arg5 = ptr; + } + result = (bool)(arg1)->loadReducedModelFromFile(arg2,(std::vector< std::string,std::allocator< std::string > > const &)*arg3,arg4,(std::vector< std::string,std::allocator< std::string > > const &)*arg5); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + return 0; +fail: + if (SWIG_IsNewObj(res3)) delete arg3; + if (SWIG_IsNewObj(res5)) delete arg5; + return 1; +} + + +int _wrap_ModelLoader_loadReducedModelFromFile__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string arg2 ; std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; @@ -71633,7 +75614,7 @@ int _wrap_ModelLoader_loadReducedModelFromFile__SWIG_0(int resc, mxArray *resv[] } -int _wrap_ModelLoader_loadReducedModelFromFile__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ModelLoader_loadReducedModelFromFile__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelLoader *arg1 = (iDynTree::ModelLoader *) 0 ; std::string arg2 ; std::vector< std::string,std::allocator< std::string > > *arg3 = 0 ; @@ -71695,7 +75676,7 @@ int _wrap_ModelLoader_loadReducedModelFromFile(int resc, mxArray *resv[], int ar int res = swig::asptr(argv[2], (std::vector< std::string,std::allocator< std::string > >**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadReducedModelFromFile__SWIG_1(resc,resv,argc,argv); + return _wrap_ModelLoader_loadReducedModelFromFile__SWIG_2(resc,resv,argc,argv); } } } @@ -71715,7 +75696,32 @@ int _wrap_ModelLoader_loadReducedModelFromFile(int resc, mxArray *resv[], int ar int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelLoader_loadReducedModelFromFile__SWIG_0(resc,resv,argc,argv); + return _wrap_ModelLoader_loadReducedModelFromFile__SWIG_1(resc,resv,argc,argv); + } + } + } + } + } + if (argc == 5) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ModelLoader, 0); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[1], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[2], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = SWIG_AsPtr_std_string(argv[3], (std::string**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + int res = swig::asptr(argv[4], (std::vector< std::string,std::allocator< std::string > >**)(0)); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ModelLoader_loadReducedModelFromFile__SWIG_0(resc,resv,argc,argv); + } } } } @@ -71724,6 +75730,7 @@ int _wrap_ModelLoader_loadReducedModelFromFile(int resc, mxArray *resv[], int ar SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ModelLoader_loadReducedModelFromFile'." " Possible C/C++ prototypes are:\n" + " iDynTree::ModelLoader::loadReducedModelFromFile(std::string const,std::vector< std::string,std::allocator< std::string > > const &,std::string const,std::vector< std::string,std::allocator< std::string > > const &)\n" " iDynTree::ModelLoader::loadReducedModelFromFile(std::string const,std::vector< std::string,std::allocator< std::string > > const &,std::string const)\n" " iDynTree::ModelLoader::loadReducedModelFromFile(std::string const,std::vector< std::string,std::allocator< std::string > > const &)\n"); return 1; @@ -71981,6 +75988,61 @@ int _wrap_ModelExporterOptions_robotExportedName_get(int resc, mxArray *resv[], } +int _wrap_ModelExporterOptions_xmlBlobs_set(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelExporterOptions *arg1 = (iDynTree::ModelExporterOptions *) 0 ; + std::vector< std::string,std::allocator< std::string > > *arg2 = (std::vector< std::string,std::allocator< std::string > > *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 = 0 ; + int res2 = 0 ; + mxArray * _out; + + if (!SWIG_check_num_args("ModelExporterOptions_xmlBlobs_set",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporterOptions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelExporterOptions_xmlBlobs_set" "', argument " "1"" of type '" "iDynTree::ModelExporterOptions *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelExporterOptions * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2,SWIGTYPE_p_std__vectorT_std__string_std__allocatorT_std__string_t_t, 0 | 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ModelExporterOptions_xmlBlobs_set" "', argument " "2"" of type '" "std::vector< std::string,std::allocator< std::string > > *""'"); + } + arg2 = reinterpret_cast< std::vector< std::string,std::allocator< std::string > > * >(argp2); + if (arg1) (arg1)->xmlBlobs = *arg2; + _out = (mxArray*)0; + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_ModelExporterOptions_xmlBlobs_get(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelExporterOptions *arg1 = (iDynTree::ModelExporterOptions *) 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + mxArray * _out; + std::vector< std::string,std::allocator< std::string > > *result = 0 ; + + if (!SWIG_check_num_args("ModelExporterOptions_xmlBlobs_get",argc,1,1,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporterOptions, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelExporterOptions_xmlBlobs_get" "', argument " "1"" of type '" "iDynTree::ModelExporterOptions *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelExporterOptions * >(argp1); + result = (std::vector< std::string,std::allocator< std::string > > *)& ((arg1)->xmlBlobs); + _out = SWIG_NewPointerObj(SWIG_as_voidptr(result), SWIGTYPE_p_std__vectorT_std__string_std__allocatorT_std__string_t_t, 0 | 0 ); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_new_ModelExporterOptions(int resc, mxArray *resv[], int argc, mxArray *argv[]) { mxArray * _out; iDynTree::ModelExporterOptions *result = 0 ; @@ -72130,20 +76192,17 @@ int _wrap_ModelExporter_setExportingOptions(int resc, mxArray *resv[], int argc, int _wrap_ModelExporter_init__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelExporter *arg1 = (iDynTree::ModelExporter *) 0 ; iDynTree::Model *arg2 = 0 ; - iDynTree::SensorsList *arg3 = 0 ; - iDynTree::ModelExporterOptions arg4 ; + iDynTree::ModelExporterOptions arg3 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; void *argp3 ; int res3 = 0 ; - void *argp4 ; - int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ModelExporter_init",argc,4,4,0)) { + if (!SWIG_check_num_args("ModelExporter_init",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporter, 0 | 0 ); @@ -72159,26 +76218,18 @@ int _wrap_ModelExporter_init__SWIG_0(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SensorsList, 0 ); - if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::SensorsList const &""'"); - } - if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::SensorsList const &""'"); - } - arg3 = reinterpret_cast< iDynTree::SensorsList * >(argp3); { - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__ModelExporterOptions, 0 ); - if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ModelExporter_init" "', argument " "4"" of type '" "iDynTree::ModelExporterOptions const""'"); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__ModelExporterOptions, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::ModelExporterOptions const""'"); } - if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "4"" of type '" "iDynTree::ModelExporterOptions const""'"); + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::ModelExporterOptions const""'"); } else { - arg4 = *(reinterpret_cast< iDynTree::ModelExporterOptions * >(argp4)); + arg3 = *(reinterpret_cast< iDynTree::ModelExporterOptions * >(argp3)); } } - result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,(iDynTree::SensorsList const &)*arg3,arg4); + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,arg3); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -72188,19 +76239,57 @@ int _wrap_ModelExporter_init__SWIG_0(int resc, mxArray *resv[], int argc, mxArra int _wrap_ModelExporter_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ModelExporter *arg1 = (iDynTree::ModelExporter *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ModelExporter_init",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporter, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ModelExporter_init" "', argument " "1"" of type '" "iDynTree::ModelExporter *""'"); + } + arg1 = reinterpret_cast< iDynTree::ModelExporter * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ModelExporter_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_ModelExporter_init__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelExporter *arg1 = (iDynTree::ModelExporter *) 0 ; iDynTree::Model *arg2 = 0 ; iDynTree::SensorsList *arg3 = 0 ; + iDynTree::ModelExporterOptions arg4 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; void *argp3 ; int res3 = 0 ; + void *argp4 ; + int res4 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ModelExporter_init",argc,3,3,0)) { + if (!SWIG_check_num_args("ModelExporter_init",argc,4,4,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporter, 0 | 0 ); @@ -72224,7 +76313,18 @@ int _wrap_ModelExporter_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::SensorsList const &""'"); } arg3 = reinterpret_cast< iDynTree::SensorsList * >(argp3); - result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,(iDynTree::SensorsList const &)*arg3); + { + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__ModelExporterOptions, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ModelExporter_init" "', argument " "4"" of type '" "iDynTree::ModelExporterOptions const""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "4"" of type '" "iDynTree::ModelExporterOptions const""'"); + } else { + arg4 = *(reinterpret_cast< iDynTree::ModelExporterOptions * >(argp4)); + } + } + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,(iDynTree::SensorsList const &)*arg3,arg4); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -72233,17 +76333,20 @@ int _wrap_ModelExporter_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArra } -int _wrap_ModelExporter_init__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_ModelExporter_init__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ModelExporter *arg1 = (iDynTree::ModelExporter *) 0 ; iDynTree::Model *arg2 = 0 ; + iDynTree::SensorsList *arg3 = 0 ; void *argp1 = 0 ; int res1 = 0 ; void *argp2 ; int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; mxArray * _out; bool result; - if (!SWIG_check_num_args("ModelExporter_init",argc,2,2,0)) { + if (!SWIG_check_num_args("ModelExporter_init",argc,3,3,0)) { SWIG_fail; } res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ModelExporter, 0 | 0 ); @@ -72259,7 +76362,15 @@ int _wrap_ModelExporter_init__SWIG_2(int resc, mxArray *resv[], int argc, mxArra SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); } arg2 = reinterpret_cast< iDynTree::Model * >(argp2); - result = (bool)(arg1)->init((iDynTree::Model const &)*arg2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__SensorsList, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::SensorsList const &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ModelExporter_init" "', argument " "3"" of type '" "iDynTree::SensorsList const &""'"); + } + arg3 = reinterpret_cast< iDynTree::SensorsList * >(argp3); + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,(iDynTree::SensorsList const &)*arg3); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -72279,7 +76390,26 @@ int _wrap_ModelExporter_init(int resc, mxArray *resv[], int argc, mxArray *argv[ int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelExporter_init__SWIG_2(resc,resv,argc,argv); + return _wrap_ModelExporter_init__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__ModelExporter, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__ModelExporterOptions, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_ModelExporter_init__SWIG_0(resc,resv,argc,argv); + } } } } @@ -72297,7 +76427,7 @@ int _wrap_ModelExporter_init(int resc, mxArray *resv[], int argc, mxArray *argv[ int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelExporter_init__SWIG_1(resc,resv,argc,argv); + return _wrap_ModelExporter_init__SWIG_3(resc,resv,argc,argv); } } } @@ -72320,7 +76450,7 @@ int _wrap_ModelExporter_init(int resc, mxArray *resv[], int argc, mxArray *argv[ int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__ModelExporterOptions, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_ModelExporter_init__SWIG_0(resc,resv,argc,argv); + return _wrap_ModelExporter_init__SWIG_2(resc,resv,argc,argv); } } } @@ -72329,9 +76459,10 @@ int _wrap_ModelExporter_init(int resc, mxArray *resv[], int argc, mxArray *argv[ SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'ModelExporter_init'." " Possible C/C++ prototypes are:\n" + " iDynTree::ModelExporter::init(iDynTree::Model const &,iDynTree::ModelExporterOptions const)\n" + " iDynTree::ModelExporter::init(iDynTree::Model const &)\n" " iDynTree::ModelExporter::init(iDynTree::Model const &,iDynTree::SensorsList const &,iDynTree::ModelExporterOptions const)\n" - " iDynTree::ModelExporter::init(iDynTree::Model const &,iDynTree::SensorsList const &)\n" - " iDynTree::ModelExporter::init(iDynTree::Model const &)\n"); + " iDynTree::ModelExporter::init(iDynTree::Model const &,iDynTree::SensorsList const &)\n"); return 1; } @@ -76038,6 +80169,41 @@ int _wrap_delete_ExtWrenchesAndJointTorquesEstimator(int resc, mxArray *resv[], } +int _wrap_ExtWrenchesAndJointTorquesEstimator_setModel(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ExtWrenchesAndJointTorquesEstimator_setModel",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ExtWrenchesAndJointTorquesEstimator, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtWrenchesAndJointTorquesEstimator_setModel" "', argument " "1"" of type '" "iDynTree::ExtWrenchesAndJointTorquesEstimator *""'"); + } + arg1 = reinterpret_cast< iDynTree::ExtWrenchesAndJointTorquesEstimator * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_setModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_setModel" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->setModel((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_ExtWrenchesAndJointTorquesEstimator_setModelAndSensors(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; iDynTree::Model *arg2 = 0 ; @@ -76432,9 +80598,9 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_submodels(int resc, mxArray *resv[ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; - iDynTree::JointPosDoubleArray *arg2 = 0 ; - iDynTree::JointDOFsDoubleArray *arg3 = 0 ; - iDynTree::JointDOFsDoubleArray *arg4 = 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::VectorDynSize *arg4 = 0 ; iDynTree::FrameIndex *arg5 = 0 ; iDynTree::Vector3 *arg6 = 0 ; iDynTree::Vector3 *arg7 = 0 ; @@ -76467,30 +80633,30 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(i SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "1"" of type '" "iDynTree::ExtWrenchesAndJointTorquesEstimator *""'"); } arg1 = reinterpret_cast< iDynTree::ExtWrenchesAndJointTorquesEstimator * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "2"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "2"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg2 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "3"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "3"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg3 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "4"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "4"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg4 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp4); + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); if (!SWIG_IsOK(ecode5)) { SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "5"" of type '" "iDynTree::FrameIndex""'"); @@ -76521,7 +80687,7 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(i SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase" "', argument " "8"" of type '" "iDynTree::Vector3 const &""'"); } arg8 = reinterpret_cast< iDynTree::Vector3 * >(argp8); - result = (bool)(arg1)->updateKinematicsFromFloatingBase((iDynTree::JointPosDoubleArray const &)*arg2,(iDynTree::JointDOFsDoubleArray const &)*arg3,(iDynTree::JointDOFsDoubleArray const &)*arg4,(iDynTree::FrameIndex const &)*arg5,(iDynTree::Vector3 const &)*arg6,(iDynTree::Vector3 const &)*arg7,(iDynTree::Vector3 const &)*arg8); + result = (bool)(arg1)->updateKinematicsFromFloatingBase((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,(iDynTree::FrameIndex const &)*arg5,(iDynTree::Vector3 const &)*arg6,(iDynTree::Vector3 const &)*arg7,(iDynTree::Vector3 const &)*arg8); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -76532,9 +80698,9 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(i int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; - iDynTree::JointPosDoubleArray *arg2 = 0 ; - iDynTree::JointDOFsDoubleArray *arg3 = 0 ; - iDynTree::JointDOFsDoubleArray *arg4 = 0 ; + iDynTree::VectorDynSize *arg2 = 0 ; + iDynTree::VectorDynSize *arg3 = 0 ; + iDynTree::VectorDynSize *arg4 = 0 ; iDynTree::FrameIndex *arg5 = 0 ; iDynTree::Vector3 *arg6 = 0 ; void *argp1 = 0 ; @@ -76561,30 +80727,30 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase(int SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "1"" of type '" "iDynTree::ExtWrenchesAndJointTorquesEstimator *""'"); } arg1 = reinterpret_cast< iDynTree::ExtWrenchesAndJointTorquesEstimator * >(argp1); - res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__JointPosDoubleArray, 0 ); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res2)) { - SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "2"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp2) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "2"" of type '" "iDynTree::JointPosDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "2"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg2 = reinterpret_cast< iDynTree::JointPosDoubleArray * >(argp2); - res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); + arg2 = reinterpret_cast< iDynTree::VectorDynSize * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res3)) { - SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "3"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp3) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "3"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "3"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg3 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp3); - res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__JointDOFsDoubleArray, 0 ); + arg3 = reinterpret_cast< iDynTree::VectorDynSize * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_iDynTree__VectorDynSize, 0 ); if (!SWIG_IsOK(res4)) { - SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "4"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); } if (!argp4) { - SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "4"" of type '" "iDynTree::JointDOFsDoubleArray const &""'"); + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "4"" of type '" "iDynTree::VectorDynSize const &""'"); } - arg4 = reinterpret_cast< iDynTree::JointDOFsDoubleArray * >(argp4); + arg4 = reinterpret_cast< iDynTree::VectorDynSize * >(argp4); ecode5 = SWIG_AsVal_ptrdiff_t(argv[4], &val5); if (!SWIG_IsOK(ecode5)) { SWIG_exception_fail(SWIG_ArgError(ecode5), "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "5"" of type '" "iDynTree::FrameIndex""'"); @@ -76599,7 +80765,7 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase(int SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase" "', argument " "6"" of type '" "iDynTree::Vector3 const &""'"); } arg6 = reinterpret_cast< iDynTree::Vector3 * >(argp6); - result = (bool)(arg1)->updateKinematicsFromFixedBase((iDynTree::JointPosDoubleArray const &)*arg2,(iDynTree::JointDOFsDoubleArray const &)*arg3,(iDynTree::JointDOFsDoubleArray const &)*arg4,(iDynTree::FrameIndex const &)*arg5,(iDynTree::Vector3 const &)*arg6); + result = (bool)(arg1)->updateKinematicsFromFixedBase((iDynTree::VectorDynSize const &)*arg2,(iDynTree::VectorDynSize const &)*arg3,(iDynTree::VectorDynSize const &)*arg4,(iDynTree::FrameIndex const &)*arg5,(iDynTree::Vector3 const &)*arg6); _out = SWIG_From_bool(static_cast< bool >(result)); if (_out) --resc, *resv++ = _out; return 0; @@ -76676,6 +80842,85 @@ int _wrap_ExtWrenchesAndJointTorquesEstimator_computeExpectedFTSensorsMeasuremen } +int _wrap_ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; + iDynTree::LinkUnknownWrenchContacts *arg2 = 0 ; + std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > *arg3 = 0 ; + std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > *arg4 = 0 ; + std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > *arg5 = 0 ; + std::vector< iDynTree::LinkIndex,std::allocator< iDynTree::LinkIndex > > *arg6 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 = 0 ; + int res3 = 0 ; + void *argp4 = 0 ; + int res4 = 0 ; + void *argp5 = 0 ; + int res5 = 0 ; + void *argp6 = 0 ; + int res6 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics",argc,6,6,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__ExtWrenchesAndJointTorquesEstimator, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "1"" of type '" "iDynTree::ExtWrenchesAndJointTorquesEstimator *""'"); + } + arg1 = reinterpret_cast< iDynTree::ExtWrenchesAndJointTorquesEstimator * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__LinkUnknownWrenchContacts, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "2"" of type '" "iDynTree::LinkUnknownWrenchContacts const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "2"" of type '" "iDynTree::LinkUnknownWrenchContacts const &""'"); + } + arg2 = reinterpret_cast< iDynTree::LinkUnknownWrenchContacts * >(argp2); + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > &""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "3"" of type '" "std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > &""'"); + } + arg3 = reinterpret_cast< std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > * >(argp3); + res4 = SWIG_ConvertPtr(argv[3], &argp4, SWIGTYPE_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t, 0 ); + if (!SWIG_IsOK(res4)) { + SWIG_exception_fail(SWIG_ArgError(res4), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "4"" of type '" "std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > &""'"); + } + if (!argp4) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "4"" of type '" "std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > &""'"); + } + arg4 = reinterpret_cast< std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > * >(argp4); + res5 = SWIG_ConvertPtr(argv[4], &argp5, SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 ); + if (!SWIG_IsOK(res5)) { + SWIG_exception_fail(SWIG_ArgError(res5), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "5"" of type '" "std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > &""'"); + } + if (!argp5) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "5"" of type '" "std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > &""'"); + } + arg5 = reinterpret_cast< std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > * >(argp5); + res6 = SWIG_ConvertPtr(argv[5], &argp6, SWIGTYPE_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t, 0 ); + if (!SWIG_IsOK(res6)) { + SWIG_exception_fail(SWIG_ArgError(res6), "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "6"" of type '" "std::vector< iDynTree::LinkIndex,std::allocator< iDynTree::LinkIndex > > &""'"); + } + if (!argp6) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics" "', argument " "6"" of type '" "std::vector< iDynTree::LinkIndex,std::allocator< iDynTree::LinkIndex > > &""'"); + } + arg6 = reinterpret_cast< std::vector< iDynTree::LinkIndex,std::allocator< iDynTree::LinkIndex > > * >(argp6); + result = (bool)(arg1)->computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics((iDynTree::LinkUnknownWrenchContacts const &)*arg2,*arg3,*arg4,*arg5,*arg6); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + int _wrap_ExtWrenchesAndJointTorquesEstimator_estimateExtWrenchesAndJointTorques(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::ExtWrenchesAndJointTorquesEstimator *arg1 = (iDynTree::ExtWrenchesAndJointTorquesEstimator *) 0 ; iDynTree::LinkUnknownWrenchContacts *arg2 = 0 ; @@ -79226,6 +83471,90 @@ int _wrap_BerdyHelper_isValid(int resc, mxArray *resv[], int argc, mxArray *argv int _wrap_BerdyHelper_init__SWIG_0(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::BerdyHelper *arg1 = (iDynTree::BerdyHelper *) 0 ; + iDynTree::Model *arg2 = 0 ; + iDynTree::BerdyOptions arg3 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + void *argp3 ; + int res3 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("BerdyHelper_init",argc,3,3,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__BerdyHelper, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyHelper_init" "', argument " "1"" of type '" "iDynTree::BerdyHelper *""'"); + } + arg1 = reinterpret_cast< iDynTree::BerdyHelper * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyHelper_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyHelper_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + { + res3 = SWIG_ConvertPtr(argv[2], &argp3, SWIGTYPE_p_iDynTree__BerdyOptions, 0 ); + if (!SWIG_IsOK(res3)) { + SWIG_exception_fail(SWIG_ArgError(res3), "in method '" "BerdyHelper_init" "', argument " "3"" of type '" "iDynTree::BerdyOptions const""'"); + } + if (!argp3) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyHelper_init" "', argument " "3"" of type '" "iDynTree::BerdyOptions const""'"); + } else { + arg3 = *(reinterpret_cast< iDynTree::BerdyOptions * >(argp3)); + } + } + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2,arg3); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_BerdyHelper_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + iDynTree::BerdyHelper *arg1 = (iDynTree::BerdyHelper *) 0 ; + iDynTree::Model *arg2 = 0 ; + void *argp1 = 0 ; + int res1 = 0 ; + void *argp2 ; + int res2 = 0 ; + mxArray * _out; + bool result; + + if (!SWIG_check_num_args("BerdyHelper_init",argc,2,2,0)) { + SWIG_fail; + } + res1 = SWIG_ConvertPtr(argv[0], &argp1,SWIGTYPE_p_iDynTree__BerdyHelper, 0 | 0 ); + if (!SWIG_IsOK(res1)) { + SWIG_exception_fail(SWIG_ArgError(res1), "in method '" "BerdyHelper_init" "', argument " "1"" of type '" "iDynTree::BerdyHelper *""'"); + } + arg1 = reinterpret_cast< iDynTree::BerdyHelper * >(argp1); + res2 = SWIG_ConvertPtr(argv[1], &argp2, SWIGTYPE_p_iDynTree__Model, 0 ); + if (!SWIG_IsOK(res2)) { + SWIG_exception_fail(SWIG_ArgError(res2), "in method '" "BerdyHelper_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + if (!argp2) { + SWIG_exception_fail(SWIG_ValueError, "invalid null reference " "in method '" "BerdyHelper_init" "', argument " "2"" of type '" "iDynTree::Model const &""'"); + } + arg2 = reinterpret_cast< iDynTree::Model * >(argp2); + result = (bool)(arg1)->init((iDynTree::Model const &)*arg2); + _out = SWIG_From_bool(static_cast< bool >(result)); + if (_out) --resc, *resv++ = _out; + return 0; +fail: + return 1; +} + + +int _wrap_BerdyHelper_init__SWIG_2(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::BerdyHelper *arg1 = (iDynTree::BerdyHelper *) 0 ; iDynTree::Model *arg2 = 0 ; iDynTree::SensorsList *arg3 = 0 ; @@ -79285,7 +83614,7 @@ int _wrap_BerdyHelper_init__SWIG_0(int resc, mxArray *resv[], int argc, mxArray } -int _wrap_BerdyHelper_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArray *argv[]) { +int _wrap_BerdyHelper_init__SWIG_3(int resc, mxArray *resv[], int argc, mxArray *argv[]) { iDynTree::BerdyHelper *arg1 = (iDynTree::BerdyHelper *) 0 ; iDynTree::Model *arg2 = 0 ; iDynTree::SensorsList *arg3 = 0 ; @@ -79332,6 +83661,39 @@ int _wrap_BerdyHelper_init__SWIG_1(int resc, mxArray *resv[], int argc, mxArray int _wrap_BerdyHelper_init(int resc, mxArray *resv[], int argc, mxArray *argv[]) { + if (argc == 2) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__BerdyHelper, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdyHelper_init__SWIG_1(resc,resv,argc,argv); + } + } + } + if (argc == 3) { + int _v; + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[0], &vptr, SWIGTYPE_p_iDynTree__BerdyHelper, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[1], &vptr, SWIGTYPE_p_iDynTree__Model, 0); + _v = SWIG_CheckState(res); + if (_v) { + void *vptr = 0; + int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__BerdyOptions, 0); + _v = SWIG_CheckState(res); + if (_v) { + return _wrap_BerdyHelper_init__SWIG_0(resc,resv,argc,argv); + } + } + } + } if (argc == 3) { int _v; void *vptr = 0; @@ -79346,7 +83708,7 @@ int _wrap_BerdyHelper_init(int resc, mxArray *resv[], int argc, mxArray *argv[]) int res = SWIG_ConvertPtr(argv[2], &vptr, SWIGTYPE_p_iDynTree__SensorsList, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdyHelper_init__SWIG_1(resc,resv,argc,argv); + return _wrap_BerdyHelper_init__SWIG_3(resc,resv,argc,argv); } } } @@ -79369,7 +83731,7 @@ int _wrap_BerdyHelper_init(int resc, mxArray *resv[], int argc, mxArray *argv[]) int res = SWIG_ConvertPtr(argv[3], &vptr, SWIGTYPE_p_iDynTree__BerdyOptions, 0); _v = SWIG_CheckState(res); if (_v) { - return _wrap_BerdyHelper_init__SWIG_0(resc,resv,argc,argv); + return _wrap_BerdyHelper_init__SWIG_2(resc,resv,argc,argv); } } } @@ -79378,6 +83740,8 @@ int _wrap_BerdyHelper_init(int resc, mxArray *resv[], int argc, mxArray *argv[]) SWIG_Error(SWIG_RuntimeError, "No matching function for overload function 'BerdyHelper_init'." " Possible C/C++ prototypes are:\n" + " iDynTree::BerdyHelper::init(iDynTree::Model const &,iDynTree::BerdyOptions const)\n" + " iDynTree::BerdyHelper::init(iDynTree::Model const &)\n" " iDynTree::BerdyHelper::init(iDynTree::Model const &,iDynTree::SensorsList const &,iDynTree::BerdyOptions const)\n" " iDynTree::BerdyHelper::init(iDynTree::Model const &,iDynTree::SensorsList const &)\n"); return 1; @@ -109364,12 +113728,6 @@ static void *_p_iDynTree__AttitudeMahonyFilterTo_p_iDynTree__IAttitudeEstimator( static void *_p_iDynTree__AttitudeQuaternionEKFTo_p_iDynTree__IAttitudeEstimator(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::IAttitudeEstimator *) ((iDynTree::AttitudeQuaternionEKF *) x)); } -static void *_p_iDynTree__RotationTo_p_iDynTree__RotationRaw(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::RotationRaw *) ((iDynTree::Rotation *) x)); -} -static void *_p_iDynTree__PositionTo_p_iDynTree__PositionRaw(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::PositionRaw *) ((iDynTree::Position *) x)); -} static void *_p_iDynTree__RevoluteJointTo_p_iDynTree__MovableJointImplT_1_1_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::MovableJointImpl< 1,1 > *) ((iDynTree::RevoluteJoint *) x)); } @@ -109377,10 +113735,7 @@ static void *_p_iDynTree__PrismaticJointTo_p_iDynTree__MovableJointImplT_1_1_t(v return (void *)((iDynTree::MovableJointImpl< 1,1 > *) ((iDynTree::PrismaticJoint *) x)); } static void *_p_iDynTree__PositionTo_p_iDynTree__VectorFixSizeT_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::VectorFixSize< 3 > *) (iDynTree::PositionRaw *) ((iDynTree::Position *) x)); -} -static void *_p_iDynTree__PositionRawTo_p_iDynTree__VectorFixSizeT_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::VectorFixSize< 3 > *) ((iDynTree::PositionRaw *) x)); + return (void *)((iDynTree::VectorFixSize< 3 > *) ((iDynTree::Position *) x)); } static void *_p_iDynTree__GeomVector3To_p_iDynTree__VectorFixSizeT_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::VectorFixSize< 3 > *) ((iDynTree::GeomVector3 *) x)); @@ -109388,6 +113743,12 @@ static void *_p_iDynTree__GeomVector3To_p_iDynTree__VectorFixSizeT_3_t(void *x, static void *_p_iDynTree__DirectionTo_p_iDynTree__VectorFixSizeT_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::VectorFixSize< 3 > *) ((iDynTree::Direction *) x)); } +static void *_p_iDynTree__JointPosDoubleArrayTo_p_iDynTree__VectorDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { + return (void *)((iDynTree::VectorDynSize *) ((iDynTree::JointPosDoubleArray *) x)); +} +static void *_p_iDynTree__JointDOFsDoubleArrayTo_p_iDynTree__VectorDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { + return (void *)((iDynTree::VectorDynSize *) ((iDynTree::JointDOFsDoubleArray *) x)); +} static void *_p_iDynTree__FrameFreeFloatingJacobianTo_p_iDynTree__MatrixDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::MatrixDynSize *) ((iDynTree::FrameFreeFloatingJacobian *) x)); } @@ -109397,12 +113758,6 @@ static void *_p_iDynTree__MomentumFreeFloatingJacobianTo_p_iDynTree__MatrixDynSi static void *_p_iDynTree__FreeFloatingMassMatrixTo_p_iDynTree__MatrixDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::MatrixDynSize *) ((iDynTree::FreeFloatingMassMatrix *) x)); } -static void *_p_iDynTree__JointPosDoubleArrayTo_p_iDynTree__VectorDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::VectorDynSize *) ((iDynTree::JointPosDoubleArray *) x)); -} -static void *_p_iDynTree__JointDOFsDoubleArrayTo_p_iDynTree__VectorDynSize(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::VectorDynSize *) ((iDynTree::JointDOFsDoubleArray *) x)); -} static void *_p_iDynTree__WrenchTo_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) (iDynTree::SpatialForceVector *) ((iDynTree::Wrench *) x)); } @@ -109412,9 +113767,6 @@ static void *_p_iDynTree__SpatialForceVectorTo_p_iDynTree__SpatialVectorT_iDynTr static void *_p_iDynTree__SpatialMomentumTo_p_iDynTree__SpatialVectorT_iDynTree__SpatialForceVector_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::SpatialVector< iDynTree::SpatialForceVector > *) (iDynTree::SpatialForceVector *) ((iDynTree::SpatialMomentum *) x)); } -static void *_p_iDynTree__SixAxisForceTorqueSensorTo_p_iDynTree__JointSensor(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::JointSensor *) ((iDynTree::SixAxisForceTorqueSensor *) x)); -} static void *_p_iDynTree__JointSensorTo_p_iDynTree__Sensor(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::Sensor *) ((iDynTree::JointSensor *) x)); } @@ -109436,6 +113788,9 @@ static void *_p_iDynTree__SixAxisForceTorqueSensorTo_p_iDynTree__Sensor(void *x, static void *_p_iDynTree__GyroscopeSensorTo_p_iDynTree__Sensor(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::Sensor *) (iDynTree::LinkSensor *) ((iDynTree::GyroscopeSensor *) x)); } +static void *_p_iDynTree__SixAxisForceTorqueSensorTo_p_iDynTree__JointSensor(void *x, int *SWIGUNUSEDPARM(newmemory)) { + return (void *)((iDynTree::JointSensor *) ((iDynTree::SixAxisForceTorqueSensor *) x)); +} static void *_p_iDynTree__BoxTo_p_iDynTree__SolidShape(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::SolidShape *) ((iDynTree::Box *) x)); } @@ -109448,9 +113803,6 @@ static void *_p_iDynTree__SphereTo_p_iDynTree__SolidShape(void *x, int *SWIGUNUS static void *_p_iDynTree__CylinderTo_p_iDynTree__SolidShape(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::SolidShape *) ((iDynTree::Cylinder *) x)); } -static void *_p_iDynTree__SpatialInertiaTo_p_iDynTree__SpatialInertiaRaw(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::SpatialInertiaRaw *) ((iDynTree::SpatialInertia *) x)); -} static void *_p_iDynTree__AccelerometerSensorTo_p_iDynTree__LinkSensor(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::LinkSensor *) ((iDynTree::AccelerometerSensor *) x)); } @@ -109475,14 +113827,11 @@ static void *_p_iDynTree__WrenchTo_p_iDynTree__SpatialForceVector(void *x, int * static void *_p_iDynTree__SpatialMomentumTo_p_iDynTree__SpatialForceVector(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::SpatialForceVector *) ((iDynTree::SpatialMomentum *) x)); } -static void *_p_iDynTree__RotationalInertiaRawTo_p_iDynTree__MatrixFixSizeT_3_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::MatrixFixSize< 3,3 > *) ((iDynTree::RotationalInertiaRaw *) x)); -} -static void *_p_iDynTree__RotationRawTo_p_iDynTree__MatrixFixSizeT_3_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::MatrixFixSize< 3,3 > *) ((iDynTree::RotationRaw *) x)); +static void *_p_iDynTree__RotationalInertiaTo_p_iDynTree__MatrixFixSizeT_3_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { + return (void *)((iDynTree::MatrixFixSize< 3,3 > *) ((iDynTree::RotationalInertia *) x)); } static void *_p_iDynTree__RotationTo_p_iDynTree__MatrixFixSizeT_3_3_t(void *x, int *SWIGUNUSEDPARM(newmemory)) { - return (void *)((iDynTree::MatrixFixSize< 3,3 > *) (iDynTree::RotationRaw *) ((iDynTree::Rotation *) x)); + return (void *)((iDynTree::MatrixFixSize< 3,3 > *) ((iDynTree::Rotation *) x)); } static void *_p_iDynTree__MovableJointImplT_1_1_tTo_p_iDynTree__IJoint(void *x, int *SWIGUNUSEDPARM(newmemory)) { return (void *)((iDynTree::IJoint *) ((iDynTree::MovableJointImpl< 1,1 > *) x)); @@ -109605,7 +113954,7 @@ static swig_type_info _swigt__p_iDynTree__LinkUnknownWrenchContacts = {"_p_iDynT static swig_type_info _swigt__p_iDynTree__LinkVelArray = {"_p_iDynTree__LinkVelArray", "iDynTree::LinkVelArray *", 0, 0, (void*)"iDynTree.LinkVelArray", 0}; static swig_type_info _swigt__p_iDynTree__LinkWrenches = {"_p_iDynTree__LinkWrenches", "iDynTree::LinkWrenches *|iDynTree::LinkNetExternalWrenches *|iDynTree::LinkInternalWrenches *|iDynTree::LinkNetTotalWrenchesWithoutGravity *", 0, 0, (void*)"iDynTree.LinkWrenches", 0}; static swig_type_info _swigt__p_iDynTree__Material = {"_p_iDynTree__Material", "iDynTree::Material *", 0, 0, (void*)"iDynTree.Material", 0}; -static swig_type_info _swigt__p_iDynTree__MatrixDynSize = {"_p_iDynTree__MatrixDynSize", "iDynTree::MatrixDynSize *", 0, 0, (void*)"iDynTree.MatrixDynSize", 0}; +static swig_type_info _swigt__p_iDynTree__MatrixDynSize = {"_p_iDynTree__MatrixDynSize", "iDynTree::MatrixDynSize *|std::vector< iDynTree::MatrixDynSize >::value_type *", 0, 0, (void*)"iDynTree.MatrixDynSize", 0}; static swig_type_info _swigt__p_iDynTree__MatrixFixSizeT_10_16_t = {"_p_iDynTree__MatrixFixSizeT_10_16_t", "iDynTree::MatrixFixSize< 10,16 > *|iDynTree::Matrix10x16 *", 0, 0, (void*)"iDynTree.Matrix10x16", 0}; static swig_type_info _swigt__p_iDynTree__MatrixFixSizeT_1_6_t = {"_p_iDynTree__MatrixFixSizeT_1_6_t", "iDynTree::Matrix1x6 *|iDynTree::MatrixFixSize< 1,6 > *", 0, 0, (void*)"iDynTree.Matrix1x6", 0}; static swig_type_info _swigt__p_iDynTree__MatrixFixSizeT_2_3_t = {"_p_iDynTree__MatrixFixSizeT_2_3_t", "iDynTree::MatrixFixSize< 2,3 > *|iDynTree::Matrix2x3 *", 0, 0, (void*)"iDynTree.Matrix2x3", 0}; @@ -109636,14 +113985,12 @@ static swig_type_info _swigt__p_iDynTree__Neighbor = {"_p_iDynTree__Neighbor", " static swig_type_info _swigt__p_iDynTree__PixelViz = {"_p_iDynTree__PixelViz", "iDynTree::PixelViz *", 0, 0, (void*)"iDynTree.PixelViz", 0}; static swig_type_info _swigt__p_iDynTree__Polygon = {"_p_iDynTree__Polygon", "iDynTree::Polygon *", 0, 0, (void*)"iDynTree.Polygon", 0}; static swig_type_info _swigt__p_iDynTree__Polygon2D = {"_p_iDynTree__Polygon2D", "iDynTree::Polygon2D *", 0, 0, (void*)"iDynTree.Polygon2D", 0}; -static swig_type_info _swigt__p_iDynTree__Position = {"_p_iDynTree__Position", "iDynTree::Position *", 0, 0, (void*)"iDynTree.Position", 0}; -static swig_type_info _swigt__p_iDynTree__PositionRaw = {"_p_iDynTree__PositionRaw", "iDynTree::PositionRaw *", 0, 0, (void*)"iDynTree.PositionRaw", 0}; +static swig_type_info _swigt__p_iDynTree__Position = {"_p_iDynTree__Position", "iDynTree::PositionRaw *|iDynTree::Position *", 0, 0, (void*)"iDynTree.Position", 0}; static swig_type_info _swigt__p_iDynTree__PrismaticJoint = {"_p_iDynTree__PrismaticJoint", "iDynTree::PrismaticJoint *", 0, 0, (void*)"iDynTree.PrismaticJoint", 0}; static swig_type_info _swigt__p_iDynTree__RevoluteJoint = {"_p_iDynTree__RevoluteJoint", "iDynTree::RevoluteJoint *", 0, 0, (void*)"iDynTree.RevoluteJoint", 0}; static swig_type_info _swigt__p_iDynTree__RigidBodyInertiaNonLinearParametrization = {"_p_iDynTree__RigidBodyInertiaNonLinearParametrization", "iDynTree::RigidBodyInertiaNonLinearParametrization *", 0, 0, (void*)"iDynTree.RigidBodyInertiaNonLinearParametrization", 0}; -static swig_type_info _swigt__p_iDynTree__Rotation = {"_p_iDynTree__Rotation", "iDynTree::Rotation *", 0, 0, (void*)"iDynTree.Rotation", 0}; -static swig_type_info _swigt__p_iDynTree__RotationRaw = {"_p_iDynTree__RotationRaw", "iDynTree::RotationRaw *", 0, 0, (void*)"iDynTree.RotationRaw", 0}; -static swig_type_info _swigt__p_iDynTree__RotationalInertiaRaw = {"_p_iDynTree__RotationalInertiaRaw", "iDynTree::RotationalInertiaRaw *", 0, 0, (void*)"iDynTree.RotationalInertiaRaw", 0}; +static swig_type_info _swigt__p_iDynTree__Rotation = {"_p_iDynTree__Rotation", "iDynTree::RotationRaw *|iDynTree::Rotation *", 0, 0, (void*)"iDynTree.Rotation", 0}; +static swig_type_info _swigt__p_iDynTree__RotationalInertia = {"_p_iDynTree__RotationalInertia", "iDynTree::RotationalInertiaRaw *|iDynTree::RotationalInertia *", 0, 0, (void*)"iDynTree.RotationalInertia", 0}; static swig_type_info _swigt__p_iDynTree__Sensor = {"_p_iDynTree__Sensor", "iDynTree::Sensor *", 0, 0, (void*)"iDynTree.Sensor", 0}; static swig_type_info _swigt__p_iDynTree__SensorsList = {"_p_iDynTree__SensorsList", "iDynTree::SensorsList *", 0, 0, (void*)"iDynTree.SensorsList", 0}; static swig_type_info _swigt__p_iDynTree__SensorsMeasurements = {"_p_iDynTree__SensorsMeasurements", "iDynTree::SensorsMeasurements *", 0, 0, (void*)"iDynTree.SensorsMeasurements", 0}; @@ -109657,7 +114004,6 @@ static swig_type_info _swigt__p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t = { static swig_type_info _swigt__p_iDynTree__SpatialAcc = {"_p_iDynTree__SpatialAcc", "iDynTree::SpatialAcc *", 0, 0, (void*)"iDynTree.SpatialAcc", 0}; static swig_type_info _swigt__p_iDynTree__SpatialForceVector = {"_p_iDynTree__SpatialForceVector", "iDynTree::SpatialVector< iDynTree::SpatialMotionVector >::DualVectorT *|iDynTree::SpatialForceVector *", 0, 0, (void*)"iDynTree.SpatialForceVector", 0}; static swig_type_info _swigt__p_iDynTree__SpatialInertia = {"_p_iDynTree__SpatialInertia", "iDynTree::SpatialInertia *", 0, 0, (void*)"iDynTree.SpatialInertia", 0}; -static swig_type_info _swigt__p_iDynTree__SpatialInertiaRaw = {"_p_iDynTree__SpatialInertiaRaw", "iDynTree::SpatialInertiaRaw *", 0, 0, (void*)"iDynTree.SpatialInertiaRaw", 0}; static swig_type_info _swigt__p_iDynTree__SpatialMomentum = {"_p_iDynTree__SpatialMomentum", "iDynTree::SpatialMomentum *", 0, 0, (void*)"iDynTree.SpatialMomentum", 0}; static swig_type_info _swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type = {"_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type", "iDynTree::SpatialForceVector::AngularVector3T *|iDynTree::SpatialMotionForceVectorT_traits< iDynTree::SpatialForceVector >::AngularVector3Type *|iDynTree::SpatialVector< iDynTree::SpatialForceVector >::AngularVector3T *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type = {"_p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type", "iDynTree::SpatialForceVector::LinearVector3T *|iDynTree::SpatialMotionForceVectorT_traits< iDynTree::SpatialForceVector >::LinearVector3Type *|iDynTree::SpatialVector< iDynTree::SpatialForceVector >::LinearVector3T *", 0, 0, (void*)0, 0}; @@ -109676,7 +114022,7 @@ static swig_type_info _swigt__p_iDynTree__Traversal = {"_p_iDynTree__Traversal", static swig_type_info _swigt__p_iDynTree__Triplets = {"_p_iDynTree__Triplets", "iDynTree::Triplets *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_iDynTree__Twist = {"_p_iDynTree__Twist", "iDynTree::Twist *", 0, 0, (void*)"iDynTree.Twist", 0}; static swig_type_info _swigt__p_iDynTree__UnknownWrenchContact = {"_p_iDynTree__UnknownWrenchContact", "iDynTree::UnknownWrenchContact *", 0, 0, (void*)"iDynTree.UnknownWrenchContact", 0}; -static swig_type_info _swigt__p_iDynTree__VectorDynSize = {"_p_iDynTree__VectorDynSize", "iDynTree::VectorDynSize *", 0, 0, (void*)"iDynTree.VectorDynSize", 0}; +static swig_type_info _swigt__p_iDynTree__VectorDynSize = {"_p_iDynTree__VectorDynSize", "iDynTree::VectorDynSize *|std::vector< iDynTree::VectorDynSize >::value_type *", 0, 0, (void*)"iDynTree.VectorDynSize", 0}; static swig_type_info _swigt__p_iDynTree__VectorFixSizeT_10_t = {"_p_iDynTree__VectorFixSizeT_10_t", "iDynTree::VectorFixSize< 10 > *|iDynTree::Vector10 *", 0, 0, (void*)"iDynTree.Vector10", 0}; static swig_type_info _swigt__p_iDynTree__VectorFixSizeT_16_t = {"_p_iDynTree__VectorFixSizeT_16_t", "iDynTree::Vector16 *|iDynTree::VectorFixSize< 16 > *", 0, 0, (void*)"iDynTree.Vector16", 0}; static swig_type_info _swigt__p_iDynTree__VectorFixSizeT_2_t = {"_p_iDynTree__VectorFixSizeT_2_t", "iDynTree::Vector2 *|iDynTree::VectorFixSize< 2 > *", 0, 0, (void*)0, 0}; @@ -109692,36 +114038,39 @@ static swig_type_info _swigt__p_iDynTree__estimateExternalWrenchesBuffers = {"_p static swig_type_info _swigt__p_index_type = {"_p_index_type", "index_type *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_iterator = {"_p_iterator", "iterator *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_pointer = {"_p_pointer", "pointer *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_ptrdiff_t = {"_p_ptrdiff_t", "::ptrdiff_t *|std::ptrdiff_t *|iDynTree::LinkIndex *|iDynTree::FrameIndex *|iDynTree::TraversalIndex *|iDynTree::JointIndex *|iDynTree::DOFIndex *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_reference = {"_p_reference", "reference *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_reverse_iterator = {"_p_reverse_iterator", "reverse_iterator *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_size_type = {"_p_size_type", "size_type *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_iDynTree__BerdyDynamicVariable_t = {"_p_std__allocatorT_iDynTree__BerdyDynamicVariable_t", "std::vector< iDynTree::BerdyDynamicVariable >::allocator_type *|std::allocator< iDynTree::BerdyDynamicVariable > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_iDynTree__BerdySensor_t = {"_p_std__allocatorT_iDynTree__BerdySensor_t", "std::allocator< iDynTree::BerdySensor > *|std::vector< iDynTree::BerdySensor >::allocator_type *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__allocatorT_iDynTree__MatrixDynSize_t = {"_p_std__allocatorT_iDynTree__MatrixDynSize_t", "std::vector< iDynTree::MatrixDynSize >::allocator_type *|std::allocator< iDynTree::MatrixDynSize > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t = {"_p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t", "std::vector< iDynTree::MatrixFixSize< 4,4 > >::allocator_type *|std::allocator< iDynTree::MatrixFixSize< 4,4 > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_iDynTree__SolidShape_p_t = {"_p_std__allocatorT_iDynTree__SolidShape_p_t", "std::allocator< iDynTree::SolidShape * > *|std::vector< iDynTree::SolidShape * >::allocator_type *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__allocatorT_iDynTree__VectorDynSize_t = {"_p_std__allocatorT_iDynTree__VectorDynSize_t", "std::vector< iDynTree::VectorDynSize >::allocator_type *|std::allocator< iDynTree::VectorDynSize > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_int_t = {"_p_std__allocatorT_int_t", "std::vector< int >::allocator_type *|std::allocator< int > *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__allocatorT_std__ptrdiff_t_t = {"_p_std__allocatorT_std__ptrdiff_t_t", "std::vector< ::ptrdiff_t >::allocator_type *|std::allocator< ::ptrdiff_t > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_std__string_t = {"_p_std__allocatorT_std__string_t", "std::vector< std::string >::allocator_type *|std::allocator< std::string > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t = {"_p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t", "std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *|std::vector< std::vector< iDynTree::SolidShape * > >::allocator_type *", 0, 0, (void*)0, 0}; -static swig_type_info _swigt__p_std__ptrdiff_t = {"_p_std__ptrdiff_t", "std::ptrdiff_t *|iDynTree::LinkIndex *|iDynTree::FrameIndex *|iDynTree::TraversalIndex *|iDynTree::JointIndex *|iDynTree::DOFIndex *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t = {"_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t", "iDynTree::Span< double,-1 >::reverse_iterator *|std::reverse_iterator< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,false > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t = {"_p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t", "std::reverse_iterator< iDynTree::details::span_iterator< iDynTree::Span< double,-1 >,true > > *|iDynTree::Span< double,-1 >::const_reverse_iterator *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__size_t = {"_p_std__size_t", "std::size_t *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__string = {"_p_std__string", "std::string *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t = {"_p_std__vectorT_iDynTree__BerdyDynamicVariable_std__allocatorT_iDynTree__BerdyDynamicVariable_t_t", "std::vector< iDynTree::BerdyDynamicVariable,std::allocator< iDynTree::BerdyDynamicVariable > > *|std::vector< iDynTree::BerdyDynamicVariable > *", 0, 0, (void*)"iDynTree.BerdyDynamicVariables", 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t = {"_p_std__vectorT_iDynTree__BerdySensor_std__allocatorT_iDynTree__BerdySensor_t_t", "std::vector< iDynTree::BerdySensor > *|std::vector< iDynTree::BerdySensor,std::allocator< iDynTree::BerdySensor > > *", 0, 0, (void*)"iDynTree.BerdySensors", 0}; -static swig_type_info _swigt__p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t = {"_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t", "std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t = {"_p_std__vectorT_iDynTree__MatrixDynSize_std__allocatorT_iDynTree__MatrixDynSize_t_t", "std::vector< iDynTree::MatrixDynSize,std::allocator< iDynTree::MatrixDynSize > > *|std::vector< iDynTree::MatrixDynSize > *", 0, 0, (void*)"iDynTree.MatrixDynSizeVector", 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__MatrixFixSizeT_4_4_t_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t_t = {"_p_std__vectorT_iDynTree__MatrixFixSizeT_4_4_t_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t_t", "std::vector< iDynTree::MatrixFixSize< 4,4 > > *|std::vector< iDynTree::Matrix4x4 > *|std::vector< iDynTree::MatrixFixSize< 4,4 >,std::allocator< iDynTree::MatrixFixSize< 4,4 > > > *|std::vector< iDynTree::Matrix4x4,std::allocator< iDynTree::Matrix4x4 > > *", 0, 0, (void*)"iDynTree.Matrix4x4Vector", 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__PixelViz_std__allocatorT_iDynTree__PixelViz_t_t = {"_p_std__vectorT_iDynTree__PixelViz_std__allocatorT_iDynTree__PixelViz_t_t", "std::vector< iDynTree::PixelViz,std::allocator< iDynTree::PixelViz > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__Polygon_std__allocatorT_iDynTree__Polygon_t_t = {"_p_std__vectorT_iDynTree__Polygon_std__allocatorT_iDynTree__Polygon_t_t", "std::vector< iDynTree::Polygon,std::allocator< iDynTree::Polygon > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t = {"_p_std__vectorT_iDynTree__Position_std__allocatorT_iDynTree__Position_t_t", "std::vector< iDynTree::Position,std::allocator< iDynTree::Position > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t = {"_p_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t", "std::vector< iDynTree::SolidShape * > *|std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > *", 0, 0, (void*)"iDynTree.SolidShapesVector", 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__Transform_std__allocatorT_iDynTree__Transform_t_t = {"_p_std__vectorT_iDynTree__Transform_std__allocatorT_iDynTree__Transform_t_t", "std::vector< iDynTree::Transform,std::allocator< iDynTree::Transform > > *", 0, 0, (void*)0, 0}; -static swig_type_info _swigt__p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t = {"_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t", "std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t = {"_p_std__vectorT_iDynTree__VectorDynSize_std__allocatorT_iDynTree__VectorDynSize_t_t", "std::vector< iDynTree::VectorDynSize,std::allocator< iDynTree::VectorDynSize > > *|std::vector< iDynTree::VectorDynSize > *", 0, 0, (void*)"iDynTree.VectorDynSizeVector", 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__VectorFixSizeT_2_t_std__allocatorT_iDynTree__VectorFixSizeT_2_t_t_t = {"_p_std__vectorT_iDynTree__VectorFixSizeT_2_t_std__allocatorT_iDynTree__VectorFixSizeT_2_t_t_t", "std::vector< iDynTree::Vector2,std::allocator< iDynTree::Vector2 > > *|std::vector< iDynTree::VectorFixSize< 2 >,std::allocator< iDynTree::VectorFixSize< 2 > > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_iDynTree__VectorFixSizeT_6_t_std__allocatorT_iDynTree__VectorFixSizeT_6_t_t_t = {"_p_std__vectorT_iDynTree__VectorFixSizeT_6_t_std__allocatorT_iDynTree__VectorFixSizeT_6_t_t_t", "std::vector< iDynTree::Vector6,std::allocator< iDynTree::Vector6 > > *|std::vector< iDynTree::VectorFixSize< 6 >,std::allocator< iDynTree::VectorFixSize< 6 > > > *", 0, 0, (void*)0, 0}; static swig_type_info _swigt__p_std__vectorT_int_std__allocatorT_int_t_t = {"_p_std__vectorT_int_std__allocatorT_int_t_t", "std::vector< int,std::allocator< int > > *|std::vector< int > *", 0, 0, (void*)"iDynTree.IntVector", 0}; static swig_type_info _swigt__p_std__vectorT_std__pairT_double_double_t_std__allocatorT_std__pairT_double_double_t_t_t = {"_p_std__vectorT_std__pairT_double_double_t_std__allocatorT_std__pairT_double_double_t_t_t", "std::vector< std::pair< double,double >,std::allocator< std::pair< double,double > > > *", 0, 0, (void*)0, 0}; -static swig_type_info _swigt__p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t = {"_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t", "std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > *|std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > *", 0, 0, (void*)0, 0}; +static swig_type_info _swigt__p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t = {"_p_std__vectorT_std__ptrdiff_t_std__allocatorT_std__ptrdiff_t_t_t", "std::vector< ::ptrdiff_t,std::allocator< ::ptrdiff_t > > *|std::vector< ::ptrdiff_t > *|std::vector< std::ptrdiff_t > *|std::vector< std::ptrdiff_t,std::allocator< std::ptrdiff_t > > *|std::vector< iDynTree::LinkIndex,std::allocator< iDynTree::LinkIndex > > *|std::vector< iDynTree::FrameIndex,std::allocator< iDynTree::FrameIndex > > *", 0, 0, (void*)"iDynTree.IndexVector", 0}; static swig_type_info _swigt__p_std__vectorT_std__string_std__allocatorT_std__string_t_t = {"_p_std__vectorT_std__string_std__allocatorT_std__string_t_t", "std::vector< std::string,std::allocator< std::string > > *|std::vector< std::string > *", 0, 0, (void*)"iDynTree.StringVector", 0}; static swig_type_info _swigt__p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t = {"_p_std__vectorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t_t", "std::vector< std::vector< iDynTree::SolidShape * > > *|std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > >,std::allocator< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > > *|std::vector< std::vector< iDynTree::SolidShape *,std::allocator< iDynTree::SolidShape * > > > *", 0, 0, (void*)"iDynTree.LinksSolidShapesVector", 0}; static swig_type_info _swigt__p_swig__MatlabSwigIterator = {"_p_swig__MatlabSwigIterator", "swig::MatlabSwigIterator *", 0, 0, (void*)"iDynTree.MatlabSwigIterator", 0}; @@ -109843,13 +114192,11 @@ static swig_type_info *swig_type_initial[] = { &_swigt__p_iDynTree__Polygon, &_swigt__p_iDynTree__Polygon2D, &_swigt__p_iDynTree__Position, - &_swigt__p_iDynTree__PositionRaw, &_swigt__p_iDynTree__PrismaticJoint, &_swigt__p_iDynTree__RevoluteJoint, &_swigt__p_iDynTree__RigidBodyInertiaNonLinearParametrization, &_swigt__p_iDynTree__Rotation, - &_swigt__p_iDynTree__RotationRaw, - &_swigt__p_iDynTree__RotationalInertiaRaw, + &_swigt__p_iDynTree__RotationalInertia, &_swigt__p_iDynTree__Sensor, &_swigt__p_iDynTree__SensorsList, &_swigt__p_iDynTree__SensorsMeasurements, @@ -109863,7 +114210,6 @@ static swig_type_info *swig_type_initial[] = { &_swigt__p_iDynTree__SpatialAcc, &_swigt__p_iDynTree__SpatialForceVector, &_swigt__p_iDynTree__SpatialInertia, - &_swigt__p_iDynTree__SpatialInertiaRaw, &_swigt__p_iDynTree__SpatialMomentum, &_swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, &_swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, @@ -109898,17 +114244,20 @@ static swig_type_info *swig_type_initial[] = { &_swigt__p_index_type, &_swigt__p_iterator, &_swigt__p_pointer, + &_swigt__p_ptrdiff_t, &_swigt__p_reference, &_swigt__p_reverse_iterator, &_swigt__p_size_type, &_swigt__p_std__allocatorT_iDynTree__BerdyDynamicVariable_t, &_swigt__p_std__allocatorT_iDynTree__BerdySensor_t, + &_swigt__p_std__allocatorT_iDynTree__MatrixDynSize_t, &_swigt__p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t, &_swigt__p_std__allocatorT_iDynTree__SolidShape_p_t, + &_swigt__p_std__allocatorT_iDynTree__VectorDynSize_t, &_swigt__p_std__allocatorT_int_t, + &_swigt__p_std__allocatorT_std__ptrdiff_t_t, &_swigt__p_std__allocatorT_std__string_t, &_swigt__p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t, - &_swigt__p_std__ptrdiff_t, &_swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, &_swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, &_swigt__p_std__size_t, @@ -110021,7 +114370,7 @@ static swig_cast_info _swigc__p_iDynTree__MatrixDynSize[] = { {&_swigt__p_iDynT static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_10_16_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_10_16_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_1_6_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_1_6_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_2_3_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_2_3_t, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_3_3_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0, 0}, {&_swigt__p_iDynTree__RotationalInertiaRaw, _p_iDynTree__RotationalInertiaRawTo_p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0}, {&_swigt__p_iDynTree__RotationRaw, _p_iDynTree__RotationRawTo_p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0}, {&_swigt__p_iDynTree__Rotation, _p_iDynTree__RotationTo_p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_3_3_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0, 0}, {&_swigt__p_iDynTree__RotationalInertia, _p_iDynTree__RotationalInertiaTo_p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0}, {&_swigt__p_iDynTree__Rotation, _p_iDynTree__RotationTo_p_iDynTree__MatrixFixSizeT_3_3_t, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_3_4_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_3_4_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_4_3_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_4_3_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__MatrixFixSizeT_4_4_t[] = { {&_swigt__p_iDynTree__MatrixFixSizeT_4_4_t, 0, 0, 0},{0, 0, 0, 0}}; @@ -110049,13 +114398,11 @@ static swig_cast_info _swigc__p_iDynTree__PixelViz[] = { {&_swigt__p_iDynTree__ static swig_cast_info _swigc__p_iDynTree__Polygon[] = { {&_swigt__p_iDynTree__Polygon, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__Polygon2D[] = { {&_swigt__p_iDynTree__Polygon2D, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__Position[] = { {&_swigt__p_iDynTree__Position, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__PositionRaw[] = { {&_swigt__p_iDynTree__Position, _p_iDynTree__PositionTo_p_iDynTree__PositionRaw, 0, 0}, {&_swigt__p_iDynTree__PositionRaw, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__PrismaticJoint[] = { {&_swigt__p_iDynTree__PrismaticJoint, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__RevoluteJoint[] = { {&_swigt__p_iDynTree__RevoluteJoint, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__RigidBodyInertiaNonLinearParametrization[] = { {&_swigt__p_iDynTree__RigidBodyInertiaNonLinearParametrization, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__Rotation[] = { {&_swigt__p_iDynTree__Rotation, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__RotationRaw[] = { {&_swigt__p_iDynTree__RotationRaw, 0, 0, 0}, {&_swigt__p_iDynTree__Rotation, _p_iDynTree__RotationTo_p_iDynTree__RotationRaw, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__RotationalInertiaRaw[] = { {&_swigt__p_iDynTree__RotationalInertiaRaw, 0, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_iDynTree__RotationalInertia[] = { {&_swigt__p_iDynTree__RotationalInertia, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__Sensor[] = { {&_swigt__p_iDynTree__JointSensor, _p_iDynTree__JointSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__AccelerometerSensor, _p_iDynTree__AccelerometerSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__ThreeAxisAngularAccelerometerSensor, _p_iDynTree__ThreeAxisAngularAccelerometerSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__ThreeAxisForceTorqueContactSensor, _p_iDynTree__ThreeAxisForceTorqueContactSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__Sensor, 0, 0, 0}, {&_swigt__p_iDynTree__SixAxisForceTorqueSensor, _p_iDynTree__SixAxisForceTorqueSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__LinkSensor, _p_iDynTree__LinkSensorTo_p_iDynTree__Sensor, 0, 0}, {&_swigt__p_iDynTree__GyroscopeSensor, _p_iDynTree__GyroscopeSensorTo_p_iDynTree__Sensor, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SensorsList[] = { {&_swigt__p_iDynTree__SensorsList, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SensorsMeasurements[] = { {&_swigt__p_iDynTree__SensorsMeasurements, 0, 0, 0},{0, 0, 0, 0}}; @@ -110069,7 +114416,6 @@ static swig_cast_info _swigc__p_iDynTree__SparseMatrixT_iDynTree__RowMajor_t[] = static swig_cast_info _swigc__p_iDynTree__SpatialAcc[] = { {&_swigt__p_iDynTree__SpatialAcc, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SpatialForceVector[] = { {&_swigt__p_iDynTree__SpatialForceVector, 0, 0, 0}, {&_swigt__p_iDynTree__Wrench, _p_iDynTree__WrenchTo_p_iDynTree__SpatialForceVector, 0, 0}, {&_swigt__p_iDynTree__SpatialMomentum, _p_iDynTree__SpatialMomentumTo_p_iDynTree__SpatialForceVector, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SpatialInertia[] = { {&_swigt__p_iDynTree__SpatialInertia, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__SpatialInertiaRaw[] = { {&_swigt__p_iDynTree__SpatialInertia, _p_iDynTree__SpatialInertiaTo_p_iDynTree__SpatialInertiaRaw, 0, 0}, {&_swigt__p_iDynTree__SpatialInertiaRaw, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SpatialMomentum[] = { {&_swigt__p_iDynTree__SpatialMomentum, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type[] = { {&_swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type[] = { {&_swigt__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, 0, 0, 0},{0, 0, 0, 0}}; @@ -110092,7 +114438,7 @@ static swig_cast_info _swigc__p_iDynTree__VectorDynSize[] = { {&_swigt__p_iDynT static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_10_t[] = { {&_swigt__p_iDynTree__VectorFixSizeT_10_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_16_t[] = { {&_swigt__p_iDynTree__VectorFixSizeT_16_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_2_t[] = { {&_swigt__p_iDynTree__VectorFixSizeT_2_t, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_3_t[] = { {&_swigt__p_iDynTree__Position, _p_iDynTree__PositionTo_p_iDynTree__VectorFixSizeT_3_t, 0, 0}, {&_swigt__p_iDynTree__VectorFixSizeT_3_t, 0, 0, 0}, {&_swigt__p_iDynTree__PositionRaw, _p_iDynTree__PositionRawTo_p_iDynTree__VectorFixSizeT_3_t, 0, 0}, {&_swigt__p_iDynTree__GeomVector3, _p_iDynTree__GeomVector3To_p_iDynTree__VectorFixSizeT_3_t, 0, 0}, {&_swigt__p_iDynTree__Direction, _p_iDynTree__DirectionTo_p_iDynTree__VectorFixSizeT_3_t, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_3_t[] = { {&_swigt__p_iDynTree__Position, _p_iDynTree__PositionTo_p_iDynTree__VectorFixSizeT_3_t, 0, 0}, {&_swigt__p_iDynTree__VectorFixSizeT_3_t, 0, 0, 0}, {&_swigt__p_iDynTree__GeomVector3, _p_iDynTree__GeomVector3To_p_iDynTree__VectorFixSizeT_3_t, 0, 0}, {&_swigt__p_iDynTree__Direction, _p_iDynTree__DirectionTo_p_iDynTree__VectorFixSizeT_3_t, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_4_t[] = { {&_swigt__p_iDynTree__VectorFixSizeT_4_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__VectorFixSizeT_6_t[] = { {&_swigt__p_iDynTree__ClassicalAcc, _p_iDynTree__ClassicalAccTo_p_iDynTree__VectorFixSizeT_6_t, 0, 0}, {&_swigt__p_iDynTree__VectorFixSizeT_6_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iDynTree__Visualizer[] = { {&_swigt__p_iDynTree__Visualizer, 0, 0, 0},{0, 0, 0, 0}}; @@ -110104,17 +114450,20 @@ static swig_cast_info _swigc__p_iDynTree__estimateExternalWrenchesBuffers[] = { static swig_cast_info _swigc__p_index_type[] = { {&_swigt__p_index_type, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_iterator[] = { {&_swigt__p_iterator, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_pointer[] = { {&_swigt__p_pointer, 0, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_ptrdiff_t[] = { {&_swigt__p_ptrdiff_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_reference[] = { {&_swigt__p_reference, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_reverse_iterator[] = { {&_swigt__p_reverse_iterator, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_size_type[] = { {&_swigt__p_size_type, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_iDynTree__BerdyDynamicVariable_t[] = { {&_swigt__p_std__allocatorT_iDynTree__BerdyDynamicVariable_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_iDynTree__BerdySensor_t[] = { {&_swigt__p_std__allocatorT_iDynTree__BerdySensor_t, 0, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_std__allocatorT_iDynTree__MatrixDynSize_t[] = { {&_swigt__p_std__allocatorT_iDynTree__MatrixDynSize_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t[] = { {&_swigt__p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_iDynTree__SolidShape_p_t[] = { {&_swigt__p_std__allocatorT_iDynTree__SolidShape_p_t, 0, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_std__allocatorT_iDynTree__VectorDynSize_t[] = { {&_swigt__p_std__allocatorT_iDynTree__VectorDynSize_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_int_t[] = { {&_swigt__p_std__allocatorT_int_t, 0, 0, 0},{0, 0, 0, 0}}; +static swig_cast_info _swigc__p_std__allocatorT_std__ptrdiff_t_t[] = { {&_swigt__p_std__allocatorT_std__ptrdiff_t_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_std__string_t[] = { {&_swigt__p_std__allocatorT_std__string_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t[] = { {&_swigt__p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t, 0, 0, 0},{0, 0, 0, 0}}; -static swig_cast_info _swigc__p_std__ptrdiff_t[] = { {&_swigt__p_std__ptrdiff_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t[] = { {&_swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t[] = { {&_swigt__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, 0, 0, 0},{0, 0, 0, 0}}; static swig_cast_info _swigc__p_std__size_t[] = { {&_swigt__p_std__size_t, 0, 0, 0},{0, 0, 0, 0}}; @@ -110255,13 +114604,11 @@ static swig_cast_info *swig_cast_initial[] = { _swigc__p_iDynTree__Polygon, _swigc__p_iDynTree__Polygon2D, _swigc__p_iDynTree__Position, - _swigc__p_iDynTree__PositionRaw, _swigc__p_iDynTree__PrismaticJoint, _swigc__p_iDynTree__RevoluteJoint, _swigc__p_iDynTree__RigidBodyInertiaNonLinearParametrization, _swigc__p_iDynTree__Rotation, - _swigc__p_iDynTree__RotationRaw, - _swigc__p_iDynTree__RotationalInertiaRaw, + _swigc__p_iDynTree__RotationalInertia, _swigc__p_iDynTree__Sensor, _swigc__p_iDynTree__SensorsList, _swigc__p_iDynTree__SensorsMeasurements, @@ -110275,7 +114622,6 @@ static swig_cast_info *swig_cast_initial[] = { _swigc__p_iDynTree__SpatialAcc, _swigc__p_iDynTree__SpatialForceVector, _swigc__p_iDynTree__SpatialInertia, - _swigc__p_iDynTree__SpatialInertiaRaw, _swigc__p_iDynTree__SpatialMomentum, _swigc__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__AngularVector3Type, _swigc__p_iDynTree__SpatialMotionForceVectorT_traitsT_iDynTree__SpatialForceVector_t__LinearVector3Type, @@ -110310,17 +114656,20 @@ static swig_cast_info *swig_cast_initial[] = { _swigc__p_index_type, _swigc__p_iterator, _swigc__p_pointer, + _swigc__p_ptrdiff_t, _swigc__p_reference, _swigc__p_reverse_iterator, _swigc__p_size_type, _swigc__p_std__allocatorT_iDynTree__BerdyDynamicVariable_t, _swigc__p_std__allocatorT_iDynTree__BerdySensor_t, + _swigc__p_std__allocatorT_iDynTree__MatrixDynSize_t, _swigc__p_std__allocatorT_iDynTree__MatrixFixSizeT_4_4_t_t, _swigc__p_std__allocatorT_iDynTree__SolidShape_p_t, + _swigc__p_std__allocatorT_iDynTree__VectorDynSize_t, _swigc__p_std__allocatorT_int_t, + _swigc__p_std__allocatorT_std__ptrdiff_t_t, _swigc__p_std__allocatorT_std__string_t, _swigc__p_std__allocatorT_std__vectorT_iDynTree__SolidShape_p_std__allocatorT_iDynTree__SolidShape_p_t_t_t, - _swigc__p_std__ptrdiff_t, _swigc__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_false_t_t, _swigc__p_std__reverse_iteratorT_iDynTree__details__span_iteratorT_iDynTree__SpanT_double__1_t_true_t_t, _swigc__p_std__size_t, @@ -110605,46 +114954,48 @@ SWIGINTERN const char* SwigConstantName(int con_id) { switch (con_id) { case 0: return "RowMajor"; case 1: return "ColumnMajor"; - case 2: return "INERTIAL_FIXED_REPRESENTATION"; - case 3: return "BODY_FIXED_REPRESENTATION"; - case 4: return "MIXED_REPRESENTATION"; - case 5: return "SIX_AXIS_FORCE_TORQUE"; - case 6: return "ACCELEROMETER"; - case 7: return "GYROSCOPE"; - case 8: return "THREE_AXIS_ANGULAR_ACCELEROMETER"; - case 9: return "THREE_AXIS_FORCE_TORQUE_CONTACT"; - case 10: return "FULL_WRENCH"; - case 11: return "PURE_FORCE"; - case 12: return "PURE_FORCE_WITH_KNOWN_DIRECTION"; - case 13: return "NO_UNKNOWNS"; - case 14: return "ORIGINAL_BERDY_FIXED_BASE"; - case 15: return "BERDY_FLOATING_BASE"; - case 16: return "BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES"; - case 17: return "LINK_BODY_PROPER_ACCELERATION"; - case 18: return "NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV"; - case 19: return "JOINT_WRENCH"; - case 20: return "DOF_TORQUE"; - case 21: return "NET_EXT_WRENCH"; - case 22: return "DOF_ACCELERATION"; - case 23: return "LINK_BODY_PROPER_CLASSICAL_ACCELERATION"; - case 24: return "SIX_AXIS_FORCE_TORQUE_SENSOR"; - case 25: return "ACCELEROMETER_SENSOR"; - case 26: return "GYROSCOPE_SENSOR"; - case 27: return "THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR"; - case 28: return "THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR"; - case 29: return "DOF_ACCELERATION_SENSOR"; - case 30: return "DOF_TORQUE_SENSOR"; - case 31: return "NET_EXT_WRENCH_SENSOR"; - case 32: return "JOINT_WRENCH_SENSOR"; - case 33: return "RCM_SENSOR"; - case 34: return "POINT_LIGHT"; - case 35: return "DIRECTIONAL_LIGHT"; - case 36: return "InverseKinematicsRotationParametrizationQuaternion"; - case 37: return "InverseKinematicsRotationParametrizationRollPitchYaw"; - case 38: return "InverseKinematicsTreatTargetAsConstraintNone"; - case 39: return "InverseKinematicsTreatTargetAsConstraintPositionOnly"; - case 40: return "InverseKinematicsTreatTargetAsConstraintRotationOnly"; - case 41: return "InverseKinematicsTreatTargetAsConstraintFull"; + case 2: return "NoJointDynamics"; + case 3: return "URDFJointDynamics"; + case 4: return "SIX_AXIS_FORCE_TORQUE"; + case 5: return "ACCELEROMETER"; + case 6: return "GYROSCOPE"; + case 7: return "THREE_AXIS_ANGULAR_ACCELEROMETER"; + case 8: return "THREE_AXIS_FORCE_TORQUE_CONTACT"; + case 9: return "INERTIAL_FIXED_REPRESENTATION"; + case 10: return "BODY_FIXED_REPRESENTATION"; + case 11: return "MIXED_REPRESENTATION"; + case 12: return "FULL_WRENCH"; + case 13: return "PURE_FORCE"; + case 14: return "PURE_FORCE_WITH_KNOWN_DIRECTION"; + case 15: return "NO_UNKNOWNS"; + case 16: return "ORIGINAL_BERDY_FIXED_BASE"; + case 17: return "BERDY_FLOATING_BASE"; + case 18: return "BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES"; + case 19: return "LINK_BODY_PROPER_ACCELERATION"; + case 20: return "NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV"; + case 21: return "JOINT_WRENCH"; + case 22: return "DOF_TORQUE"; + case 23: return "NET_EXT_WRENCH"; + case 24: return "DOF_ACCELERATION"; + case 25: return "LINK_BODY_PROPER_CLASSICAL_ACCELERATION"; + case 26: return "SIX_AXIS_FORCE_TORQUE_SENSOR"; + case 27: return "ACCELEROMETER_SENSOR"; + case 28: return "GYROSCOPE_SENSOR"; + case 29: return "THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR"; + case 30: return "THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR"; + case 31: return "DOF_ACCELERATION_SENSOR"; + case 32: return "DOF_TORQUE_SENSOR"; + case 33: return "NET_EXT_WRENCH_SENSOR"; + case 34: return "JOINT_WRENCH_SENSOR"; + case 35: return "RCM_SENSOR"; + case 36: return "POINT_LIGHT"; + case 37: return "DIRECTIONAL_LIGHT"; + case 38: return "InverseKinematicsRotationParametrizationQuaternion"; + case 39: return "InverseKinematicsRotationParametrizationRollPitchYaw"; + case 40: return "InverseKinematicsTreatTargetAsConstraintNone"; + case 41: return "InverseKinematicsTreatTargetAsConstraintPositionOnly"; + case 42: return "InverseKinematicsTreatTargetAsConstraintRotationOnly"; + case 43: return "InverseKinematicsTreatTargetAsConstraintFull"; default: return 0; } } @@ -110677,46 +115028,48 @@ SWIGINTERN int swigConstant(int SWIGUNUSEDPARM(resc), mxArray *resv[], int argc, switch (con_id) { case 0: *resv = SWIG_Matlab_SetConstant(module_ns,"RowMajor",SWIG_From_int(static_cast< int >(iDynTree::RowMajor)));; break; case 1: *resv = SWIG_Matlab_SetConstant(module_ns,"ColumnMajor",SWIG_From_int(static_cast< int >(iDynTree::ColumnMajor)));; break; - case 2: *resv = SWIG_Matlab_SetConstant(module_ns,"INERTIAL_FIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::INERTIAL_FIXED_REPRESENTATION)));; break; - case 3: *resv = SWIG_Matlab_SetConstant(module_ns,"BODY_FIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::BODY_FIXED_REPRESENTATION)));; break; - case 4: *resv = SWIG_Matlab_SetConstant(module_ns,"MIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::MIXED_REPRESENTATION)));; break; - case 5: *resv = SWIG_Matlab_SetConstant(module_ns,"SIX_AXIS_FORCE_TORQUE",SWIG_From_int(static_cast< int >(iDynTree::SIX_AXIS_FORCE_TORQUE)));; break; - case 6: *resv = SWIG_Matlab_SetConstant(module_ns,"ACCELEROMETER",SWIG_From_int(static_cast< int >(iDynTree::ACCELEROMETER)));; break; - case 7: *resv = SWIG_Matlab_SetConstant(module_ns,"GYROSCOPE",SWIG_From_int(static_cast< int >(iDynTree::GYROSCOPE)));; break; - case 8: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_ANGULAR_ACCELEROMETER",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER)));; break; - case 9: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_FORCE_TORQUE_CONTACT",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT)));; break; - case 10: *resv = SWIG_Matlab_SetConstant(module_ns,"FULL_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::FULL_WRENCH)));; break; - case 11: *resv = SWIG_Matlab_SetConstant(module_ns,"PURE_FORCE",SWIG_From_int(static_cast< int >(iDynTree::PURE_FORCE)));; break; - case 12: *resv = SWIG_Matlab_SetConstant(module_ns,"PURE_FORCE_WITH_KNOWN_DIRECTION",SWIG_From_int(static_cast< int >(iDynTree::PURE_FORCE_WITH_KNOWN_DIRECTION)));; break; - case 13: *resv = SWIG_Matlab_SetConstant(module_ns,"NO_UNKNOWNS",SWIG_From_int(static_cast< int >(iDynTree::NO_UNKNOWNS)));; break; - case 14: *resv = SWIG_Matlab_SetConstant(module_ns,"ORIGINAL_BERDY_FIXED_BASE",SWIG_From_int(static_cast< int >(iDynTree::ORIGINAL_BERDY_FIXED_BASE)));; break; - case 15: *resv = SWIG_Matlab_SetConstant(module_ns,"BERDY_FLOATING_BASE",SWIG_From_int(static_cast< int >(iDynTree::BERDY_FLOATING_BASE)));; break; - case 16: *resv = SWIG_Matlab_SetConstant(module_ns,"BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES",SWIG_From_int(static_cast< int >(iDynTree::BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES)));; break; - case 17: *resv = SWIG_Matlab_SetConstant(module_ns,"LINK_BODY_PROPER_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::LINK_BODY_PROPER_ACCELERATION)));; break; - case 18: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV",SWIG_From_int(static_cast< int >(iDynTree::NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV)));; break; - case 19: *resv = SWIG_Matlab_SetConstant(module_ns,"JOINT_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::JOINT_WRENCH)));; break; - case 20: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_TORQUE",SWIG_From_int(static_cast< int >(iDynTree::DOF_TORQUE)));; break; - case 21: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_EXT_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::NET_EXT_WRENCH)));; break; - case 22: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::DOF_ACCELERATION)));; break; - case 23: *resv = SWIG_Matlab_SetConstant(module_ns,"LINK_BODY_PROPER_CLASSICAL_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::LINK_BODY_PROPER_CLASSICAL_ACCELERATION)));; break; - case 24: *resv = SWIG_Matlab_SetConstant(module_ns,"SIX_AXIS_FORCE_TORQUE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::SIX_AXIS_FORCE_TORQUE_SENSOR)));; break; - case 25: *resv = SWIG_Matlab_SetConstant(module_ns,"ACCELEROMETER_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::ACCELEROMETER_SENSOR)));; break; - case 26: *resv = SWIG_Matlab_SetConstant(module_ns,"GYROSCOPE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::GYROSCOPE_SENSOR)));; break; - case 27: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR)));; break; - case 28: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR)));; break; - case 29: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_ACCELERATION_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::DOF_ACCELERATION_SENSOR)));; break; - case 30: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_TORQUE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::DOF_TORQUE_SENSOR)));; break; - case 31: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_EXT_WRENCH_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::NET_EXT_WRENCH_SENSOR)));; break; - case 32: *resv = SWIG_Matlab_SetConstant(module_ns,"JOINT_WRENCH_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::JOINT_WRENCH_SENSOR)));; break; - case 33: *resv = SWIG_Matlab_SetConstant(module_ns,"RCM_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::RCM_SENSOR)));; break; - case 34: *resv = SWIG_Matlab_SetConstant(module_ns,"POINT_LIGHT",SWIG_From_int(static_cast< int >(iDynTree::POINT_LIGHT)));; break; - case 35: *resv = SWIG_Matlab_SetConstant(module_ns,"DIRECTIONAL_LIGHT",SWIG_From_int(static_cast< int >(iDynTree::DIRECTIONAL_LIGHT)));; break; - case 36: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsRotationParametrizationQuaternion",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsRotationParametrizationQuaternion)));; break; - case 37: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsRotationParametrizationRollPitchYaw",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsRotationParametrizationRollPitchYaw)));; break; - case 38: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintNone",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintNone)));; break; - case 39: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintPositionOnly",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintPositionOnly)));; break; - case 40: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintRotationOnly",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintRotationOnly)));; break; - case 41: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintFull",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintFull)));; break; + case 2: *resv = SWIG_Matlab_SetConstant(module_ns,"NoJointDynamics",SWIG_From_int(static_cast< int >(iDynTree::NoJointDynamics)));; break; + case 3: *resv = SWIG_Matlab_SetConstant(module_ns,"URDFJointDynamics",SWIG_From_int(static_cast< int >(iDynTree::URDFJointDynamics)));; break; + case 4: *resv = SWIG_Matlab_SetConstant(module_ns,"SIX_AXIS_FORCE_TORQUE",SWIG_From_int(static_cast< int >(iDynTree::SIX_AXIS_FORCE_TORQUE)));; break; + case 5: *resv = SWIG_Matlab_SetConstant(module_ns,"ACCELEROMETER",SWIG_From_int(static_cast< int >(iDynTree::ACCELEROMETER)));; break; + case 6: *resv = SWIG_Matlab_SetConstant(module_ns,"GYROSCOPE",SWIG_From_int(static_cast< int >(iDynTree::GYROSCOPE)));; break; + case 7: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_ANGULAR_ACCELEROMETER",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER)));; break; + case 8: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_FORCE_TORQUE_CONTACT",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT)));; break; + case 9: *resv = SWIG_Matlab_SetConstant(module_ns,"INERTIAL_FIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::INERTIAL_FIXED_REPRESENTATION)));; break; + case 10: *resv = SWIG_Matlab_SetConstant(module_ns,"BODY_FIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::BODY_FIXED_REPRESENTATION)));; break; + case 11: *resv = SWIG_Matlab_SetConstant(module_ns,"MIXED_REPRESENTATION",SWIG_From_int(static_cast< int >(iDynTree::MIXED_REPRESENTATION)));; break; + case 12: *resv = SWIG_Matlab_SetConstant(module_ns,"FULL_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::FULL_WRENCH)));; break; + case 13: *resv = SWIG_Matlab_SetConstant(module_ns,"PURE_FORCE",SWIG_From_int(static_cast< int >(iDynTree::PURE_FORCE)));; break; + case 14: *resv = SWIG_Matlab_SetConstant(module_ns,"PURE_FORCE_WITH_KNOWN_DIRECTION",SWIG_From_int(static_cast< int >(iDynTree::PURE_FORCE_WITH_KNOWN_DIRECTION)));; break; + case 15: *resv = SWIG_Matlab_SetConstant(module_ns,"NO_UNKNOWNS",SWIG_From_int(static_cast< int >(iDynTree::NO_UNKNOWNS)));; break; + case 16: *resv = SWIG_Matlab_SetConstant(module_ns,"ORIGINAL_BERDY_FIXED_BASE",SWIG_From_int(static_cast< int >(iDynTree::ORIGINAL_BERDY_FIXED_BASE)));; break; + case 17: *resv = SWIG_Matlab_SetConstant(module_ns,"BERDY_FLOATING_BASE",SWIG_From_int(static_cast< int >(iDynTree::BERDY_FLOATING_BASE)));; break; + case 18: *resv = SWIG_Matlab_SetConstant(module_ns,"BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES",SWIG_From_int(static_cast< int >(iDynTree::BERDY_FLOATING_BASE_NON_COLLOCATED_EXT_WRENCHES)));; break; + case 19: *resv = SWIG_Matlab_SetConstant(module_ns,"LINK_BODY_PROPER_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::LINK_BODY_PROPER_ACCELERATION)));; break; + case 20: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV",SWIG_From_int(static_cast< int >(iDynTree::NET_INT_AND_EXT_WRENCHES_ON_LINK_WITHOUT_GRAV)));; break; + case 21: *resv = SWIG_Matlab_SetConstant(module_ns,"JOINT_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::JOINT_WRENCH)));; break; + case 22: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_TORQUE",SWIG_From_int(static_cast< int >(iDynTree::DOF_TORQUE)));; break; + case 23: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_EXT_WRENCH",SWIG_From_int(static_cast< int >(iDynTree::NET_EXT_WRENCH)));; break; + case 24: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::DOF_ACCELERATION)));; break; + case 25: *resv = SWIG_Matlab_SetConstant(module_ns,"LINK_BODY_PROPER_CLASSICAL_ACCELERATION",SWIG_From_int(static_cast< int >(iDynTree::LINK_BODY_PROPER_CLASSICAL_ACCELERATION)));; break; + case 26: *resv = SWIG_Matlab_SetConstant(module_ns,"SIX_AXIS_FORCE_TORQUE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::SIX_AXIS_FORCE_TORQUE_SENSOR)));; break; + case 27: *resv = SWIG_Matlab_SetConstant(module_ns,"ACCELEROMETER_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::ACCELEROMETER_SENSOR)));; break; + case 28: *resv = SWIG_Matlab_SetConstant(module_ns,"GYROSCOPE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::GYROSCOPE_SENSOR)));; break; + case 29: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_ANGULAR_ACCELEROMETER_SENSOR)));; break; + case 30: *resv = SWIG_Matlab_SetConstant(module_ns,"THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::THREE_AXIS_FORCE_TORQUE_CONTACT_SENSOR)));; break; + case 31: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_ACCELERATION_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::DOF_ACCELERATION_SENSOR)));; break; + case 32: *resv = SWIG_Matlab_SetConstant(module_ns,"DOF_TORQUE_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::DOF_TORQUE_SENSOR)));; break; + case 33: *resv = SWIG_Matlab_SetConstant(module_ns,"NET_EXT_WRENCH_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::NET_EXT_WRENCH_SENSOR)));; break; + case 34: *resv = SWIG_Matlab_SetConstant(module_ns,"JOINT_WRENCH_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::JOINT_WRENCH_SENSOR)));; break; + case 35: *resv = SWIG_Matlab_SetConstant(module_ns,"RCM_SENSOR",SWIG_From_int(static_cast< int >(iDynTree::RCM_SENSOR)));; break; + case 36: *resv = SWIG_Matlab_SetConstant(module_ns,"POINT_LIGHT",SWIG_From_int(static_cast< int >(iDynTree::POINT_LIGHT)));; break; + case 37: *resv = SWIG_Matlab_SetConstant(module_ns,"DIRECTIONAL_LIGHT",SWIG_From_int(static_cast< int >(iDynTree::DIRECTIONAL_LIGHT)));; break; + case 38: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsRotationParametrizationQuaternion",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsRotationParametrizationQuaternion)));; break; + case 39: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsRotationParametrizationRollPitchYaw",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsRotationParametrizationRollPitchYaw)));; break; + case 40: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintNone",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintNone)));; break; + case 41: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintPositionOnly",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintPositionOnly)));; break; + case 42: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintRotationOnly",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintRotationOnly)));; break; + case 43: *resv = SWIG_Matlab_SetConstant(module_ns,"InverseKinematicsTreatTargetAsConstraintFull",SWIG_From_int(static_cast< int >(iDynTree::InverseKinematicsTreatTargetAsConstraintFull)));; break; default: SWIG_Error(SWIG_RuntimeError, "No such constant."); return 1; @@ -110797,2047 +115150,2130 @@ SWIGINTERN const char* SwigFunctionName(int fcn_id) { case 68: return "IntVector_reserve"; case 69: return "IntVector_capacity"; case 70: return "delete_IntVector"; - case 71: return "BerdySensors_pop"; - case 72: return "BerdySensors_brace"; - case 73: return "BerdySensors_setbrace"; - case 74: return "BerdySensors_append"; - case 75: return "BerdySensors_empty"; - case 76: return "BerdySensors_size"; - case 77: return "BerdySensors_swap"; - case 78: return "BerdySensors_begin"; - case 79: return "BerdySensors_end"; - case 80: return "BerdySensors_rbegin"; - case 81: return "BerdySensors_rend"; - case 82: return "BerdySensors_clear"; - case 83: return "BerdySensors_get_allocator"; - case 84: return "BerdySensors_pop_back"; - case 85: return "BerdySensors_erase"; - case 86: return "new_BerdySensors"; - case 87: return "BerdySensors_push_back"; - case 88: return "BerdySensors_front"; - case 89: return "BerdySensors_back"; - case 90: return "BerdySensors_assign"; - case 91: return "BerdySensors_resize"; - case 92: return "BerdySensors_insert"; - case 93: return "BerdySensors_reserve"; - case 94: return "BerdySensors_capacity"; - case 95: return "delete_BerdySensors"; - case 96: return "BerdyDynamicVariables_pop"; - case 97: return "BerdyDynamicVariables_brace"; - case 98: return "BerdyDynamicVariables_setbrace"; - case 99: return "BerdyDynamicVariables_append"; - case 100: return "BerdyDynamicVariables_empty"; - case 101: return "BerdyDynamicVariables_size"; - case 102: return "BerdyDynamicVariables_swap"; - case 103: return "BerdyDynamicVariables_begin"; - case 104: return "BerdyDynamicVariables_end"; - case 105: return "BerdyDynamicVariables_rbegin"; - case 106: return "BerdyDynamicVariables_rend"; - case 107: return "BerdyDynamicVariables_clear"; - case 108: return "BerdyDynamicVariables_get_allocator"; - case 109: return "BerdyDynamicVariables_pop_back"; - case 110: return "BerdyDynamicVariables_erase"; - case 111: return "new_BerdyDynamicVariables"; - case 112: return "BerdyDynamicVariables_push_back"; - case 113: return "BerdyDynamicVariables_front"; - case 114: return "BerdyDynamicVariables_back"; - case 115: return "BerdyDynamicVariables_assign"; - case 116: return "BerdyDynamicVariables_resize"; - case 117: return "BerdyDynamicVariables_insert"; - case 118: return "BerdyDynamicVariables_reserve"; - case 119: return "BerdyDynamicVariables_capacity"; - case 120: return "delete_BerdyDynamicVariables"; - case 121: return "_wrap_reportInfo"; - case 122: return "_wrap_reportDebug"; - case 123: return "IndexRange_offset_get"; - case 124: return "IndexRange_offset_set"; - case 125: return "IndexRange_size_get"; - case 126: return "IndexRange_size_set"; - case 127: return "IndexRange_isValid"; - case 128: return "IndexRange_InvalidRange"; - case 129: return "new_IndexRange"; - case 130: return "delete_IndexRange"; - case 131: return "_wrap_checkDoublesAreEqual"; - case 132: return "new_MatrixDynSize"; - case 133: return "delete_MatrixDynSize"; - case 134: return "MatrixDynSize_paren"; - case 135: return "MatrixDynSize_getVal"; - case 136: return "MatrixDynSize_setVal"; - case 137: return "MatrixDynSize_rows"; - case 138: return "MatrixDynSize_cols"; - case 139: return "MatrixDynSize_data"; - case 140: return "MatrixDynSize_zero"; - case 141: return "MatrixDynSize_resize"; - case 142: return "MatrixDynSize_reserve"; - case 143: return "MatrixDynSize_capacity"; - case 144: return "MatrixDynSize_shrink_to_fit"; - case 145: return "MatrixDynSize_fillRowMajorBuffer"; - case 146: return "MatrixDynSize_fillColMajorBuffer"; - case 147: return "MatrixDynSize_toString"; - case 148: return "MatrixDynSize_display"; - case 149: return "MatrixDynSize_toMatlab"; - case 150: return "MatrixDynSize_fromMatlab"; - case 151: return "new_SparseMatrixRowMajor"; - case 152: return "delete_SparseMatrixRowMajor"; - case 153: return "SparseMatrixRowMajor_numberOfNonZeros"; - case 154: return "SparseMatrixRowMajor_resize"; - case 155: return "SparseMatrixRowMajor_reserve"; - case 156: return "SparseMatrixRowMajor_zero"; - case 157: return "SparseMatrixRowMajor_setFromConstTriplets"; - case 158: return "SparseMatrixRowMajor_setFromTriplets"; - case 159: return "SparseMatrixRowMajor_sparseMatrixFromTriplets"; - case 160: return "SparseMatrixRowMajor_paren"; - case 161: return "SparseMatrixRowMajor_getValue"; - case 162: return "SparseMatrixRowMajor_setValue"; - case 163: return "SparseMatrixRowMajor_rows"; - case 164: return "SparseMatrixRowMajor_columns"; - case 165: return "SparseMatrixRowMajor_description"; - case 166: return "SparseMatrixRowMajor_toMatlab"; - case 167: return "SparseMatrixRowMajor_toMatlabDense"; - case 168: return "SparseMatrixRowMajor_fromMatlab"; - case 169: return "new_SparseMatrixColMajor"; - case 170: return "delete_SparseMatrixColMajor"; - case 171: return "SparseMatrixColMajor_numberOfNonZeros"; - case 172: return "SparseMatrixColMajor_resize"; - case 173: return "SparseMatrixColMajor_reserve"; - case 174: return "SparseMatrixColMajor_zero"; - case 175: return "SparseMatrixColMajor_setFromConstTriplets"; - case 176: return "SparseMatrixColMajor_setFromTriplets"; - case 177: return "SparseMatrixColMajor_sparseMatrixFromTriplets"; - case 178: return "SparseMatrixColMajor_paren"; - case 179: return "SparseMatrixColMajor_getValue"; - case 180: return "SparseMatrixColMajor_setValue"; - case 181: return "SparseMatrixColMajor_rows"; - case 182: return "SparseMatrixColMajor_columns"; - case 183: return "SparseMatrixColMajor_description"; - case 184: return "SparseMatrixColMajor_toMatlab"; - case 185: return "SparseMatrixColMajor_toMatlabDense"; - case 186: return "SparseMatrixColMajor_fromMatlab"; - case 187: return "new_VectorDynSize"; - case 188: return "delete_VectorDynSize"; - case 189: return "VectorDynSize_paren"; - case 190: return "VectorDynSize_brace"; - case 191: return "VectorDynSize_getVal"; - case 192: return "VectorDynSize_setVal"; - case 193: return "VectorDynSize_cbegin"; - case 194: return "VectorDynSize_cend"; - case 195: return "VectorDynSize_begin"; - case 196: return "VectorDynSize_end"; - case 197: return "VectorDynSize_size"; - case 198: return "VectorDynSize_data"; - case 199: return "VectorDynSize_zero"; - case 200: return "VectorDynSize_reserve"; - case 201: return "VectorDynSize_resize"; - case 202: return "VectorDynSize_shrink_to_fit"; - case 203: return "VectorDynSize_capacity"; - case 204: return "VectorDynSize_fillBuffer"; - case 205: return "VectorDynSize_toString"; - case 206: return "VectorDynSize_display"; - case 207: return "VectorDynSize_toMatlab"; - case 208: return "VectorDynSize_fromMatlab"; - case 209: return "new_Matrix1x6"; - case 210: return "Matrix1x6_paren"; - case 211: return "Matrix1x6_getVal"; - case 212: return "Matrix1x6_setVal"; - case 213: return "Matrix1x6_rows"; - case 214: return "Matrix1x6_cols"; - case 215: return "Matrix1x6_data"; - case 216: return "Matrix1x6_zero"; - case 217: return "Matrix1x6_fillRowMajorBuffer"; - case 218: return "Matrix1x6_fillColMajorBuffer"; - case 219: return "Matrix1x6_toString"; - case 220: return "Matrix1x6_display"; - case 221: return "Matrix1x6_toMatlab"; - case 222: return "Matrix1x6_fromMatlab"; - case 223: return "delete_Matrix1x6"; - case 224: return "new_Matrix2x3"; - case 225: return "Matrix2x3_paren"; - case 226: return "Matrix2x3_getVal"; - case 227: return "Matrix2x3_setVal"; - case 228: return "Matrix2x3_rows"; - case 229: return "Matrix2x3_cols"; - case 230: return "Matrix2x3_data"; - case 231: return "Matrix2x3_zero"; - case 232: return "Matrix2x3_fillRowMajorBuffer"; - case 233: return "Matrix2x3_fillColMajorBuffer"; - case 234: return "Matrix2x3_toString"; - case 235: return "Matrix2x3_display"; - case 236: return "Matrix2x3_toMatlab"; - case 237: return "Matrix2x3_fromMatlab"; - case 238: return "delete_Matrix2x3"; - case 239: return "new_Matrix3x3"; - case 240: return "Matrix3x3_paren"; - case 241: return "Matrix3x3_getVal"; - case 242: return "Matrix3x3_setVal"; - case 243: return "Matrix3x3_rows"; - case 244: return "Matrix3x3_cols"; - case 245: return "Matrix3x3_data"; - case 246: return "Matrix3x3_zero"; - case 247: return "Matrix3x3_fillRowMajorBuffer"; - case 248: return "Matrix3x3_fillColMajorBuffer"; - case 249: return "Matrix3x3_toString"; - case 250: return "Matrix3x3_display"; - case 251: return "Matrix3x3_toMatlab"; - case 252: return "Matrix3x3_fromMatlab"; - case 253: return "delete_Matrix3x3"; - case 254: return "new_Matrix4x4"; - case 255: return "Matrix4x4_paren"; - case 256: return "Matrix4x4_getVal"; - case 257: return "Matrix4x4_setVal"; - case 258: return "Matrix4x4_rows"; - case 259: return "Matrix4x4_cols"; - case 260: return "Matrix4x4_data"; - case 261: return "Matrix4x4_zero"; - case 262: return "Matrix4x4_fillRowMajorBuffer"; - case 263: return "Matrix4x4_fillColMajorBuffer"; - case 264: return "Matrix4x4_toString"; - case 265: return "Matrix4x4_display"; - case 266: return "Matrix4x4_toMatlab"; - case 267: return "Matrix4x4_fromMatlab"; - case 268: return "delete_Matrix4x4"; - case 269: return "new_Matrix6x6"; - case 270: return "Matrix6x6_paren"; - case 271: return "Matrix6x6_getVal"; - case 272: return "Matrix6x6_setVal"; - case 273: return "Matrix6x6_rows"; - case 274: return "Matrix6x6_cols"; - case 275: return "Matrix6x6_data"; - case 276: return "Matrix6x6_zero"; - case 277: return "Matrix6x6_fillRowMajorBuffer"; - case 278: return "Matrix6x6_fillColMajorBuffer"; - case 279: return "Matrix6x6_toString"; - case 280: return "Matrix6x6_display"; - case 281: return "Matrix6x6_toMatlab"; - case 282: return "Matrix6x6_fromMatlab"; - case 283: return "delete_Matrix6x6"; - case 284: return "new_Matrix6x10"; - case 285: return "Matrix6x10_paren"; - case 286: return "Matrix6x10_getVal"; - case 287: return "Matrix6x10_setVal"; - case 288: return "Matrix6x10_rows"; - case 289: return "Matrix6x10_cols"; - case 290: return "Matrix6x10_data"; - case 291: return "Matrix6x10_zero"; - case 292: return "Matrix6x10_fillRowMajorBuffer"; - case 293: return "Matrix6x10_fillColMajorBuffer"; - case 294: return "Matrix6x10_toString"; - case 295: return "Matrix6x10_display"; - case 296: return "Matrix6x10_toMatlab"; - case 297: return "Matrix6x10_fromMatlab"; - case 298: return "delete_Matrix6x10"; - case 299: return "new_Matrix10x16"; - case 300: return "Matrix10x16_paren"; - case 301: return "Matrix10x16_getVal"; - case 302: return "Matrix10x16_setVal"; - case 303: return "Matrix10x16_rows"; - case 304: return "Matrix10x16_cols"; - case 305: return "Matrix10x16_data"; - case 306: return "Matrix10x16_zero"; - case 307: return "Matrix10x16_fillRowMajorBuffer"; - case 308: return "Matrix10x16_fillColMajorBuffer"; - case 309: return "Matrix10x16_toString"; - case 310: return "Matrix10x16_display"; - case 311: return "Matrix10x16_toMatlab"; - case 312: return "Matrix10x16_fromMatlab"; - case 313: return "delete_Matrix10x16"; - case 314: return "new_Vector3"; - case 315: return "Vector3_paren"; - case 316: return "Vector3_brace"; - case 317: return "Vector3_getVal"; - case 318: return "Vector3_setVal"; - case 319: return "Vector3_cbegin"; - case 320: return "Vector3_cend"; - case 321: return "Vector3_begin"; - case 322: return "Vector3_end"; - case 323: return "Vector3_size"; - case 324: return "Vector3_data"; - case 325: return "Vector3_zero"; - case 326: return "Vector3_fillBuffer"; - case 327: return "Vector3_toString"; - case 328: return "Vector3_display"; - case 329: return "Vector3_toMatlab"; - case 330: return "Vector3_fromMatlab"; - case 331: return "delete_Vector3"; - case 332: return "new_Vector4"; - case 333: return "Vector4_paren"; - case 334: return "Vector4_brace"; - case 335: return "Vector4_getVal"; - case 336: return "Vector4_setVal"; - case 337: return "Vector4_cbegin"; - case 338: return "Vector4_cend"; - case 339: return "Vector4_begin"; - case 340: return "Vector4_end"; - case 341: return "Vector4_size"; - case 342: return "Vector4_data"; - case 343: return "Vector4_zero"; - case 344: return "Vector4_fillBuffer"; - case 345: return "Vector4_toString"; - case 346: return "Vector4_display"; - case 347: return "Vector4_toMatlab"; - case 348: return "Vector4_fromMatlab"; - case 349: return "delete_Vector4"; - case 350: return "new_Vector6"; - case 351: return "Vector6_paren"; - case 352: return "Vector6_brace"; - case 353: return "Vector6_getVal"; - case 354: return "Vector6_setVal"; - case 355: return "Vector6_cbegin"; - case 356: return "Vector6_cend"; - case 357: return "Vector6_begin"; - case 358: return "Vector6_end"; - case 359: return "Vector6_size"; - case 360: return "Vector6_data"; - case 361: return "Vector6_zero"; - case 362: return "Vector6_fillBuffer"; - case 363: return "Vector6_toString"; - case 364: return "Vector6_display"; - case 365: return "Vector6_toMatlab"; - case 366: return "Vector6_fromMatlab"; - case 367: return "delete_Vector6"; - case 368: return "new_Vector10"; - case 369: return "Vector10_paren"; - case 370: return "Vector10_brace"; - case 371: return "Vector10_getVal"; - case 372: return "Vector10_setVal"; - case 373: return "Vector10_cbegin"; - case 374: return "Vector10_cend"; - case 375: return "Vector10_begin"; - case 376: return "Vector10_end"; - case 377: return "Vector10_size"; - case 378: return "Vector10_data"; - case 379: return "Vector10_zero"; - case 380: return "Vector10_fillBuffer"; - case 381: return "Vector10_toString"; - case 382: return "Vector10_display"; - case 383: return "Vector10_toMatlab"; - case 384: return "Vector10_fromMatlab"; - case 385: return "delete_Vector10"; - case 386: return "new_Vector16"; - case 387: return "Vector16_paren"; - case 388: return "Vector16_brace"; - case 389: return "Vector16_getVal"; - case 390: return "Vector16_setVal"; - case 391: return "Vector16_cbegin"; - case 392: return "Vector16_cend"; - case 393: return "Vector16_begin"; - case 394: return "Vector16_end"; - case 395: return "Vector16_size"; - case 396: return "Vector16_data"; - case 397: return "Vector16_zero"; - case 398: return "Vector16_fillBuffer"; - case 399: return "Vector16_toString"; - case 400: return "Vector16_display"; - case 401: return "Vector16_toMatlab"; - case 402: return "Vector16_fromMatlab"; - case 403: return "delete_Vector16"; - case 404: return "new_PositionRaw"; - case 405: return "PositionRaw_changePoint"; - case 406: return "PositionRaw_changeRefPoint"; - case 407: return "PositionRaw_compose"; - case 408: return "PositionRaw_inverse"; - case 409: return "PositionRaw_changePointOf"; - case 410: return "PositionRaw_toString"; - case 411: return "PositionRaw_display"; - case 412: return "delete_PositionRaw"; - case 413: return "new_Position"; - case 414: return "Position_changePoint"; - case 415: return "Position_changeRefPoint"; - case 416: return "Position_changeCoordinateFrame"; - case 417: return "Position_compose"; - case 418: return "Position_inverse"; - case 419: return "Position_changePointOf"; - case 420: return "Position_plus"; - case 421: return "Position_minus"; - case 422: return "Position_uminus"; - case 423: return "Position_mtimes"; - case 424: return "Position_toString"; - case 425: return "Position_display"; - case 426: return "Position_Zero"; - case 427: return "delete_Position"; - case 428: return "new_GeomVector3"; - case 429: return "GeomVector3_changeCoordFrame"; - case 430: return "GeomVector3_compose"; - case 431: return "GeomVector3_inverse"; - case 432: return "GeomVector3_dot"; - case 433: return "GeomVector3_plus"; - case 434: return "GeomVector3_minus"; - case 435: return "GeomVector3_uminus"; - case 436: return "GeomVector3_exp"; - case 437: return "GeomVector3_cross"; - case 438: return "delete_GeomVector3"; - case 439: return "new_SpatialMotionVectorBase"; - case 440: return "SpatialMotionVectorBase_getLinearVec3"; - case 441: return "SpatialMotionVectorBase_getAngularVec3"; - case 442: return "SpatialMotionVectorBase_setLinearVec3"; - case 443: return "SpatialMotionVectorBase_setAngularVec3"; - case 444: return "SpatialMotionVectorBase_paren"; - case 445: return "SpatialMotionVectorBase_getVal"; - case 446: return "SpatialMotionVectorBase_setVal"; - case 447: return "SpatialMotionVectorBase_size"; - case 448: return "SpatialMotionVectorBase_zero"; - case 449: return "SpatialMotionVectorBase_changePoint"; - case 450: return "SpatialMotionVectorBase_changeCoordFrame"; - case 451: return "SpatialMotionVectorBase_compose"; - case 452: return "SpatialMotionVectorBase_inverse"; - case 453: return "SpatialMotionVectorBase_dot"; - case 454: return "SpatialMotionVectorBase_plus"; - case 455: return "SpatialMotionVectorBase_minus"; - case 456: return "SpatialMotionVectorBase_uminus"; - case 457: return "SpatialMotionVectorBase_Zero"; - case 458: return "SpatialMotionVectorBase_asVector"; - case 459: return "SpatialMotionVectorBase_toString"; - case 460: return "SpatialMotionVectorBase_display"; - case 461: return "SpatialMotionVectorBase_toMatlab"; - case 462: return "SpatialMotionVectorBase_fromMatlab"; - case 463: return "delete_SpatialMotionVectorBase"; - case 464: return "new_SpatialForceVectorBase"; - case 465: return "SpatialForceVectorBase_getLinearVec3"; - case 466: return "SpatialForceVectorBase_getAngularVec3"; - case 467: return "SpatialForceVectorBase_setLinearVec3"; - case 468: return "SpatialForceVectorBase_setAngularVec3"; - case 469: return "SpatialForceVectorBase_paren"; - case 470: return "SpatialForceVectorBase_getVal"; - case 471: return "SpatialForceVectorBase_setVal"; - case 472: return "SpatialForceVectorBase_size"; - case 473: return "SpatialForceVectorBase_zero"; - case 474: return "SpatialForceVectorBase_changePoint"; - case 475: return "SpatialForceVectorBase_changeCoordFrame"; - case 476: return "SpatialForceVectorBase_compose"; - case 477: return "SpatialForceVectorBase_inverse"; - case 478: return "SpatialForceVectorBase_dot"; - case 479: return "SpatialForceVectorBase_plus"; - case 480: return "SpatialForceVectorBase_minus"; - case 481: return "SpatialForceVectorBase_uminus"; - case 482: return "SpatialForceVectorBase_Zero"; - case 483: return "SpatialForceVectorBase_asVector"; - case 484: return "SpatialForceVectorBase_toString"; - case 485: return "SpatialForceVectorBase_display"; - case 486: return "SpatialForceVectorBase_toMatlab"; - case 487: return "SpatialForceVectorBase_fromMatlab"; - case 488: return "delete_SpatialForceVectorBase"; - case 489: return "new_Dummy"; - case 490: return "delete_Dummy"; - case 491: return "new_SpatialMotionVector"; - case 492: return "SpatialMotionVector_mtimes"; - case 493: return "SpatialMotionVector_cross"; - case 494: return "SpatialMotionVector_asCrossProductMatrix"; - case 495: return "SpatialMotionVector_asCrossProductMatrixWrench"; - case 496: return "SpatialMotionVector_exp"; - case 497: return "delete_SpatialMotionVector"; - case 498: return "new_SpatialForceVector"; - case 499: return "delete_SpatialForceVector"; - case 500: return "SpatialForceVector_mtimes"; - case 501: return "new_Twist"; - case 502: return "Twist_plus"; - case 503: return "Twist_minus"; - case 504: return "Twist_uminus"; - case 505: return "Twist_mtimes"; - case 506: return "delete_Twist"; - case 507: return "new_Wrench"; - case 508: return "Wrench_plus"; - case 509: return "Wrench_minus"; - case 510: return "Wrench_uminus"; - case 511: return "delete_Wrench"; - case 512: return "new_SpatialMomentum"; - case 513: return "SpatialMomentum_plus"; - case 514: return "SpatialMomentum_minus"; - case 515: return "SpatialMomentum_uminus"; - case 516: return "delete_SpatialMomentum"; - case 517: return "new_SpatialAcc"; - case 518: return "SpatialAcc_plus"; - case 519: return "SpatialAcc_minus"; - case 520: return "SpatialAcc_uminus"; - case 521: return "delete_SpatialAcc"; - case 522: return "new_ClassicalAcc"; - case 523: return "ClassicalAcc_changeCoordFrame"; - case 524: return "ClassicalAcc_Zero"; - case 525: return "ClassicalAcc_fromSpatial"; - case 526: return "ClassicalAcc_toSpatial"; - case 527: return "delete_ClassicalAcc"; - case 528: return "new_Direction"; - case 529: return "Direction_Normalize"; - case 530: return "Direction_isParallel"; - case 531: return "Direction_isPerpendicular"; - case 532: return "Direction_reverse"; - case 533: return "Direction_toString"; - case 534: return "Direction_display"; - case 535: return "Direction_Default"; - case 536: return "delete_Direction"; - case 537: return "new_Axis"; - case 538: return "Axis_getDirection"; - case 539: return "Axis_getOrigin"; - case 540: return "Axis_setDirection"; - case 541: return "Axis_setOrigin"; - case 542: return "Axis_getRotationTransform"; - case 543: return "Axis_getRotationTransformDerivative"; - case 544: return "Axis_getRotationTwist"; - case 545: return "Axis_getRotationSpatialAcc"; - case 546: return "Axis_getTranslationTransform"; - case 547: return "Axis_getTranslationTransformDerivative"; - case 548: return "Axis_getTranslationTwist"; - case 549: return "Axis_getTranslationSpatialAcc"; - case 550: return "Axis_isParallel"; - case 551: return "Axis_reverse"; - case 552: return "Axis_toString"; - case 553: return "Axis_display"; - case 554: return "delete_Axis"; - case 555: return "new_RotationalInertiaRaw"; - case 556: return "RotationalInertiaRaw_Zero"; - case 557: return "delete_RotationalInertiaRaw"; - case 558: return "new_SpatialInertiaRaw"; - case 559: return "SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass"; - case 560: return "SpatialInertiaRaw_getMass"; - case 561: return "SpatialInertiaRaw_getCenterOfMass"; - case 562: return "SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin"; - case 563: return "SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass"; - case 564: return "SpatialInertiaRaw_combine"; - case 565: return "SpatialInertiaRaw_multiply"; - case 566: return "SpatialInertiaRaw_zero"; - case 567: return "delete_SpatialInertiaRaw"; - case 568: return "new_SpatialInertia"; - case 569: return "SpatialInertia_combine"; - case 570: return "SpatialInertia_asMatrix"; - case 571: return "SpatialInertia_applyInverse"; - case 572: return "SpatialInertia_getInverse"; - case 573: return "SpatialInertia_plus"; - case 574: return "SpatialInertia_mtimes"; - case 575: return "SpatialInertia_biasWrench"; - case 576: return "SpatialInertia_biasWrenchDerivative"; - case 577: return "SpatialInertia_Zero"; - case 578: return "SpatialInertia_asVector"; - case 579: return "SpatialInertia_fromVector"; - case 580: return "SpatialInertia_isPhysicallyConsistent"; - case 581: return "SpatialInertia_momentumRegressor"; - case 582: return "SpatialInertia_momentumDerivativeRegressor"; - case 583: return "SpatialInertia_momentumDerivativeSlotineLiRegressor"; - case 584: return "delete_SpatialInertia"; - case 585: return "new_ArticulatedBodyInertia"; - case 586: return "ArticulatedBodyInertia_getLinearLinearSubmatrix"; - case 587: return "ArticulatedBodyInertia_getLinearAngularSubmatrix"; - case 588: return "ArticulatedBodyInertia_getAngularAngularSubmatrix"; - case 589: return "ArticulatedBodyInertia_combine"; - case 590: return "ArticulatedBodyInertia_applyInverse"; - case 591: return "ArticulatedBodyInertia_asMatrix"; - case 592: return "ArticulatedBodyInertia_getInverse"; - case 593: return "ArticulatedBodyInertia_plus"; - case 594: return "ArticulatedBodyInertia_minus"; - case 595: return "ArticulatedBodyInertia_mtimes"; - case 596: return "ArticulatedBodyInertia_zero"; - case 597: return "ArticulatedBodyInertia_ABADyadHelper"; - case 598: return "ArticulatedBodyInertia_ABADyadHelperLin"; - case 599: return "delete_ArticulatedBodyInertia"; - case 600: return "RigidBodyInertiaNonLinearParametrization_mass_get"; - case 601: return "RigidBodyInertiaNonLinearParametrization_mass_set"; - case 602: return "RigidBodyInertiaNonLinearParametrization_com_get"; - case 603: return "RigidBodyInertiaNonLinearParametrization_com_set"; - case 604: return "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get"; - case 605: return "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set"; - case 606: return "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get"; - case 607: return "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set"; - case 608: return "RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform"; - case 609: return "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia"; - case 610: return "RigidBodyInertiaNonLinearParametrization_fromInertialParameters"; - case 611: return "RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia"; - case 612: return "RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent"; - case 613: return "RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec"; - case 614: return "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec"; - case 615: return "RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec"; - case 616: return "new_RigidBodyInertiaNonLinearParametrization"; - case 617: return "delete_RigidBodyInertiaNonLinearParametrization"; - case 618: return "new_RotationRaw"; - case 619: return "RotationRaw_changeOrientFrame"; - case 620: return "RotationRaw_changeRefOrientFrame"; - case 621: return "RotationRaw_compose"; - case 622: return "RotationRaw_inverse2"; - case 623: return "RotationRaw_changeCoordFrameOf"; - case 624: return "RotationRaw_RotX"; - case 625: return "RotationRaw_RotY"; - case 626: return "RotationRaw_RotZ"; - case 627: return "RotationRaw_RPY"; - case 628: return "RotationRaw_Identity"; - case 629: return "RotationRaw_toString"; - case 630: return "RotationRaw_display"; - case 631: return "delete_RotationRaw"; - case 632: return "new_Rotation"; - case 633: return "Rotation_changeOrientFrame"; - case 634: return "Rotation_changeRefOrientFrame"; - case 635: return "Rotation_changeCoordinateFrame"; - case 636: return "Rotation_compose"; - case 637: return "Rotation_inverse2"; - case 638: return "Rotation_changeCoordFrameOf"; - case 639: return "Rotation_inverse"; - case 640: return "Rotation_mtimes"; - case 641: return "Rotation_log"; - case 642: return "Rotation_fromQuaternion"; - case 643: return "Rotation_getRPY"; - case 644: return "Rotation_asRPY"; - case 645: return "Rotation_getQuaternion"; - case 646: return "Rotation_asQuaternion"; - case 647: return "Rotation_RotX"; - case 648: return "Rotation_RotY"; - case 649: return "Rotation_RotZ"; - case 650: return "Rotation_RotAxis"; - case 651: return "Rotation_RotAxisDerivative"; - case 652: return "Rotation_RPY"; - case 653: return "Rotation_RPYRightTrivializedDerivative"; - case 654: return "Rotation_RPYRightTrivializedDerivativeRateOfChange"; - case 655: return "Rotation_RPYRightTrivializedDerivativeInverse"; - case 656: return "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange"; - case 657: return "Rotation_QuaternionRightTrivializedDerivative"; - case 658: return "Rotation_QuaternionRightTrivializedDerivativeInverse"; - case 659: return "Rotation_Identity"; - case 660: return "Rotation_RotationFromQuaternion"; - case 661: return "Rotation_leftJacobian"; - case 662: return "Rotation_leftJacobianInverse"; - case 663: return "Rotation_toString"; - case 664: return "Rotation_display"; - case 665: return "delete_Rotation"; - case 666: return "new_Transform"; - case 667: return "Transform_fromHomogeneousTransform"; - case 668: return "Transform_getRotation"; - case 669: return "Transform_getPosition"; - case 670: return "Transform_setRotation"; - case 671: return "Transform_setPosition"; - case 672: return "Transform_compose"; - case 673: return "Transform_inverse2"; - case 674: return "Transform_inverse"; - case 675: return "Transform_mtimes"; - case 676: return "Transform_Identity"; - case 677: return "Transform_asHomogeneousTransform"; - case 678: return "Transform_asAdjointTransform"; - case 679: return "Transform_asAdjointTransformWrench"; - case 680: return "Transform_log"; - case 681: return "Transform_toString"; - case 682: return "Transform_display"; - case 683: return "delete_Transform"; - case 684: return "new_TransformDerivative"; - case 685: return "delete_TransformDerivative"; - case 686: return "TransformDerivative_getRotationDerivative"; - case 687: return "TransformDerivative_getPositionDerivative"; - case 688: return "TransformDerivative_setRotationDerivative"; - case 689: return "TransformDerivative_setPositionDerivative"; - case 690: return "TransformDerivative_Zero"; - case 691: return "TransformDerivative_asHomogeneousTransformDerivative"; - case 692: return "TransformDerivative_asAdjointTransformDerivative"; - case 693: return "TransformDerivative_asAdjointTransformWrenchDerivative"; - case 694: return "TransformDerivative_mtimes"; - case 695: return "TransformDerivative_derivativeOfInverse"; - case 696: return "TransformDerivative_transform"; - case 697: return "dynamic_extent_get"; - case 698: return "DynamicSpan_extent_get"; - case 699: return "new_DynamicSpan"; - case 700: return "delete_DynamicSpan"; - case 701: return "DynamicSpan_first"; - case 702: return "DynamicSpan_last"; - case 703: return "DynamicSpan_subspan"; - case 704: return "DynamicSpan_size"; - case 705: return "DynamicSpan_size_bytes"; - case 706: return "DynamicSpan_empty"; - case 707: return "DynamicSpan_brace"; - case 708: return "DynamicSpan_getVal"; - case 709: return "DynamicSpan_setVal"; - case 710: return "DynamicSpan_at"; - case 711: return "DynamicSpan_paren"; - case 712: return "DynamicSpan_begin"; - case 713: return "DynamicSpan_end"; - case 714: return "DynamicSpan_cbegin"; - case 715: return "DynamicSpan_cend"; - case 716: return "DynamicSpan_rbegin"; - case 717: return "DynamicSpan_rend"; - case 718: return "DynamicSpan_crbegin"; - case 719: return "DynamicSpan_crend"; - case 720: return "new_DynamicMatrixView"; - case 721: return "DynamicMatrixView_storageOrder"; - case 722: return "DynamicMatrixView_paren"; - case 723: return "DynamicMatrixView_rows"; - case 724: return "DynamicMatrixView_cols"; - case 725: return "DynamicMatrixView_block"; - case 726: return "delete_DynamicMatrixView"; - case 727: return "LINK_INVALID_INDEX_get"; - case 728: return "LINK_INVALID_INDEX_set"; - case 729: return "LINK_INVALID_NAME_get"; - case 730: return "LINK_INVALID_NAME_set"; - case 731: return "JOINT_INVALID_INDEX_get"; - case 732: return "JOINT_INVALID_INDEX_set"; - case 733: return "JOINT_INVALID_NAME_get"; - case 734: return "JOINT_INVALID_NAME_set"; - case 735: return "DOF_INVALID_INDEX_get"; - case 736: return "DOF_INVALID_INDEX_set"; - case 737: return "DOF_INVALID_NAME_get"; - case 738: return "DOF_INVALID_NAME_set"; - case 739: return "FRAME_INVALID_INDEX_get"; - case 740: return "FRAME_INVALID_INDEX_set"; - case 741: return "FRAME_INVALID_NAME_get"; - case 742: return "FRAME_INVALID_NAME_set"; - case 743: return "TRAVERSAL_INVALID_INDEX_get"; - case 744: return "TRAVERSAL_INVALID_INDEX_set"; - case 745: return "new_LinkPositions"; - case 746: return "LinkPositions_resize"; - case 747: return "LinkPositions_isConsistent"; - case 748: return "LinkPositions_getNrOfLinks"; - case 749: return "LinkPositions_paren"; - case 750: return "LinkPositions_toString"; - case 751: return "delete_LinkPositions"; - case 752: return "new_LinkWrenches"; - case 753: return "LinkWrenches_resize"; - case 754: return "LinkWrenches_isConsistent"; - case 755: return "LinkWrenches_getNrOfLinks"; - case 756: return "LinkWrenches_paren"; - case 757: return "LinkWrenches_toString"; - case 758: return "LinkWrenches_zero"; - case 759: return "delete_LinkWrenches"; - case 760: return "new_LinkInertias"; - case 761: return "LinkInertias_resize"; - case 762: return "LinkInertias_isConsistent"; - case 763: return "LinkInertias_paren"; - case 764: return "delete_LinkInertias"; - case 765: return "new_LinkArticulatedBodyInertias"; - case 766: return "LinkArticulatedBodyInertias_resize"; - case 767: return "LinkArticulatedBodyInertias_isConsistent"; - case 768: return "LinkArticulatedBodyInertias_paren"; - case 769: return "delete_LinkArticulatedBodyInertias"; - case 770: return "new_LinkVelArray"; - case 771: return "LinkVelArray_resize"; - case 772: return "LinkVelArray_isConsistent"; - case 773: return "LinkVelArray_getNrOfLinks"; - case 774: return "LinkVelArray_paren"; - case 775: return "LinkVelArray_toString"; - case 776: return "delete_LinkVelArray"; - case 777: return "new_LinkAccArray"; - case 778: return "LinkAccArray_resize"; - case 779: return "LinkAccArray_isConsistent"; - case 780: return "LinkAccArray_paren"; - case 781: return "LinkAccArray_getNrOfLinks"; - case 782: return "LinkAccArray_toString"; - case 783: return "delete_LinkAccArray"; - case 784: return "new_Link"; - case 785: return "Link_inertia"; - case 786: return "Link_setInertia"; - case 787: return "Link_getInertia"; - case 788: return "Link_setIndex"; - case 789: return "Link_getIndex"; - case 790: return "delete_Link"; - case 791: return "delete_IJoint"; - case 792: return "IJoint_clone"; - case 793: return "IJoint_getNrOfPosCoords"; - case 794: return "IJoint_getNrOfDOFs"; - case 795: return "IJoint_setAttachedLinks"; - case 796: return "IJoint_setRestTransform"; - case 797: return "IJoint_getFirstAttachedLink"; - case 798: return "IJoint_getSecondAttachedLink"; - case 799: return "IJoint_getRestTransform"; - case 800: return "IJoint_getTransform"; - case 801: return "IJoint_getTransformDerivative"; - case 802: return "IJoint_getMotionSubspaceVector"; - case 803: return "IJoint_computeChildPosVelAcc"; - case 804: return "IJoint_computeChildVelAcc"; - case 805: return "IJoint_computeChildVel"; - case 806: return "IJoint_computeChildAcc"; - case 807: return "IJoint_computeChildBiasAcc"; - case 808: return "IJoint_computeJointTorque"; - case 809: return "IJoint_setIndex"; - case 810: return "IJoint_getIndex"; - case 811: return "IJoint_setPosCoordsOffset"; - case 812: return "IJoint_getPosCoordsOffset"; - case 813: return "IJoint_setDOFsOffset"; - case 814: return "IJoint_getDOFsOffset"; - case 815: return "IJoint_hasPosLimits"; - case 816: return "IJoint_enablePosLimits"; - case 817: return "IJoint_getPosLimits"; - case 818: return "IJoint_getMinPosLimit"; - case 819: return "IJoint_getMaxPosLimit"; - case 820: return "IJoint_setPosLimits"; - case 821: return "IJoint_isRevoluteJoint"; - case 822: return "IJoint_isFixedJoint"; - case 823: return "IJoint_isPrismaticJoint"; - case 824: return "IJoint_asRevoluteJoint"; - case 825: return "IJoint_asFixedJoint"; - case 826: return "IJoint_asPrismaticJoint"; - case 827: return "new_FixedJoint"; - case 828: return "delete_FixedJoint"; - case 829: return "FixedJoint_clone"; - case 830: return "FixedJoint_getNrOfPosCoords"; - case 831: return "FixedJoint_getNrOfDOFs"; - case 832: return "FixedJoint_setAttachedLinks"; - case 833: return "FixedJoint_setRestTransform"; - case 834: return "FixedJoint_getFirstAttachedLink"; - case 835: return "FixedJoint_getSecondAttachedLink"; - case 836: return "FixedJoint_getRestTransform"; - case 837: return "FixedJoint_getTransform"; - case 838: return "FixedJoint_getTransformDerivative"; - case 839: return "FixedJoint_getMotionSubspaceVector"; - case 840: return "FixedJoint_computeChildPosVelAcc"; - case 841: return "FixedJoint_computeChildVelAcc"; - case 842: return "FixedJoint_computeChildVel"; - case 843: return "FixedJoint_computeChildAcc"; - case 844: return "FixedJoint_computeChildBiasAcc"; - case 845: return "FixedJoint_computeJointTorque"; - case 846: return "FixedJoint_setIndex"; - case 847: return "FixedJoint_getIndex"; - case 848: return "FixedJoint_setPosCoordsOffset"; - case 849: return "FixedJoint_getPosCoordsOffset"; - case 850: return "FixedJoint_setDOFsOffset"; - case 851: return "FixedJoint_getDOFsOffset"; - case 852: return "FixedJoint_hasPosLimits"; - case 853: return "FixedJoint_enablePosLimits"; - case 854: return "FixedJoint_getPosLimits"; - case 855: return "FixedJoint_getMinPosLimit"; - case 856: return "FixedJoint_getMaxPosLimit"; - case 857: return "FixedJoint_setPosLimits"; - case 858: return "delete_MovableJointImpl1"; - case 859: return "MovableJointImpl1_getNrOfPosCoords"; - case 860: return "MovableJointImpl1_getNrOfDOFs"; - case 861: return "MovableJointImpl1_setIndex"; - case 862: return "MovableJointImpl1_getIndex"; - case 863: return "MovableJointImpl1_setPosCoordsOffset"; - case 864: return "MovableJointImpl1_getPosCoordsOffset"; - case 865: return "MovableJointImpl1_setDOFsOffset"; - case 866: return "MovableJointImpl1_getDOFsOffset"; - case 867: return "delete_MovableJointImpl2"; - case 868: return "MovableJointImpl2_getNrOfPosCoords"; - case 869: return "MovableJointImpl2_getNrOfDOFs"; - case 870: return "MovableJointImpl2_setIndex"; - case 871: return "MovableJointImpl2_getIndex"; - case 872: return "MovableJointImpl2_setPosCoordsOffset"; - case 873: return "MovableJointImpl2_getPosCoordsOffset"; - case 874: return "MovableJointImpl2_setDOFsOffset"; - case 875: return "MovableJointImpl2_getDOFsOffset"; - case 876: return "delete_MovableJointImpl3"; - case 877: return "MovableJointImpl3_getNrOfPosCoords"; - case 878: return "MovableJointImpl3_getNrOfDOFs"; - case 879: return "MovableJointImpl3_setIndex"; - case 880: return "MovableJointImpl3_getIndex"; - case 881: return "MovableJointImpl3_setPosCoordsOffset"; - case 882: return "MovableJointImpl3_getPosCoordsOffset"; - case 883: return "MovableJointImpl3_setDOFsOffset"; - case 884: return "MovableJointImpl3_getDOFsOffset"; - case 885: return "delete_MovableJointImpl4"; - case 886: return "MovableJointImpl4_getNrOfPosCoords"; - case 887: return "MovableJointImpl4_getNrOfDOFs"; - case 888: return "MovableJointImpl4_setIndex"; - case 889: return "MovableJointImpl4_getIndex"; - case 890: return "MovableJointImpl4_setPosCoordsOffset"; - case 891: return "MovableJointImpl4_getPosCoordsOffset"; - case 892: return "MovableJointImpl4_setDOFsOffset"; - case 893: return "MovableJointImpl4_getDOFsOffset"; - case 894: return "delete_MovableJointImpl5"; - case 895: return "MovableJointImpl5_getNrOfPosCoords"; - case 896: return "MovableJointImpl5_getNrOfDOFs"; - case 897: return "MovableJointImpl5_setIndex"; - case 898: return "MovableJointImpl5_getIndex"; - case 899: return "MovableJointImpl5_setPosCoordsOffset"; - case 900: return "MovableJointImpl5_getPosCoordsOffset"; - case 901: return "MovableJointImpl5_setDOFsOffset"; - case 902: return "MovableJointImpl5_getDOFsOffset"; - case 903: return "delete_MovableJointImpl6"; - case 904: return "MovableJointImpl6_getNrOfPosCoords"; - case 905: return "MovableJointImpl6_getNrOfDOFs"; - case 906: return "MovableJointImpl6_setIndex"; - case 907: return "MovableJointImpl6_getIndex"; - case 908: return "MovableJointImpl6_setPosCoordsOffset"; - case 909: return "MovableJointImpl6_getPosCoordsOffset"; - case 910: return "MovableJointImpl6_setDOFsOffset"; - case 911: return "MovableJointImpl6_getDOFsOffset"; - case 912: return "new_RevoluteJoint"; - case 913: return "delete_RevoluteJoint"; - case 914: return "RevoluteJoint_clone"; - case 915: return "RevoluteJoint_setAttachedLinks"; - case 916: return "RevoluteJoint_setRestTransform"; - case 917: return "RevoluteJoint_setAxis"; - case 918: return "RevoluteJoint_getFirstAttachedLink"; - case 919: return "RevoluteJoint_getSecondAttachedLink"; - case 920: return "RevoluteJoint_getAxis"; - case 921: return "RevoluteJoint_getRestTransform"; - case 922: return "RevoluteJoint_getTransform"; - case 923: return "RevoluteJoint_getTransformDerivative"; - case 924: return "RevoluteJoint_getMotionSubspaceVector"; - case 925: return "RevoluteJoint_computeChildPosVelAcc"; - case 926: return "RevoluteJoint_computeChildVel"; - case 927: return "RevoluteJoint_computeChildVelAcc"; - case 928: return "RevoluteJoint_computeChildAcc"; - case 929: return "RevoluteJoint_computeChildBiasAcc"; - case 930: return "RevoluteJoint_computeJointTorque"; - case 931: return "RevoluteJoint_hasPosLimits"; - case 932: return "RevoluteJoint_enablePosLimits"; - case 933: return "RevoluteJoint_getPosLimits"; - case 934: return "RevoluteJoint_getMinPosLimit"; - case 935: return "RevoluteJoint_getMaxPosLimit"; - case 936: return "RevoluteJoint_setPosLimits"; - case 937: return "new_PrismaticJoint"; - case 938: return "delete_PrismaticJoint"; - case 939: return "PrismaticJoint_clone"; - case 940: return "PrismaticJoint_setAttachedLinks"; - case 941: return "PrismaticJoint_setRestTransform"; - case 942: return "PrismaticJoint_setAxis"; - case 943: return "PrismaticJoint_getFirstAttachedLink"; - case 944: return "PrismaticJoint_getSecondAttachedLink"; - case 945: return "PrismaticJoint_getAxis"; - case 946: return "PrismaticJoint_getRestTransform"; - case 947: return "PrismaticJoint_getTransform"; - case 948: return "PrismaticJoint_getTransformDerivative"; - case 949: return "PrismaticJoint_getMotionSubspaceVector"; - case 950: return "PrismaticJoint_computeChildPosVelAcc"; - case 951: return "PrismaticJoint_computeChildVel"; - case 952: return "PrismaticJoint_computeChildVelAcc"; - case 953: return "PrismaticJoint_computeChildAcc"; - case 954: return "PrismaticJoint_computeChildBiasAcc"; - case 955: return "PrismaticJoint_computeJointTorque"; - case 956: return "PrismaticJoint_hasPosLimits"; - case 957: return "PrismaticJoint_enablePosLimits"; - case 958: return "PrismaticJoint_getPosLimits"; - case 959: return "PrismaticJoint_getMinPosLimit"; - case 960: return "PrismaticJoint_getMaxPosLimit"; - case 961: return "PrismaticJoint_setPosLimits"; - case 962: return "new_Traversal"; - case 963: return "delete_Traversal"; - case 964: return "Traversal_getNrOfVisitedLinks"; - case 965: return "Traversal_getLink"; - case 966: return "Traversal_getBaseLink"; - case 967: return "Traversal_getParentLink"; - case 968: return "Traversal_getParentJoint"; - case 969: return "Traversal_getParentLinkFromLinkIndex"; - case 970: return "Traversal_getParentJointFromLinkIndex"; - case 971: return "Traversal_getTraversalIndexFromLinkIndex"; - case 972: return "Traversal_reset"; - case 973: return "Traversal_addTraversalBase"; - case 974: return "Traversal_addTraversalElement"; - case 975: return "Traversal_isParentOf"; - case 976: return "Traversal_getChildLinkIndexFromJointIndex"; - case 977: return "Traversal_getParentLinkIndexFromJointIndex"; - case 978: return "Traversal_toString"; - case 979: return "new_Material"; - case 980: return "Material_name"; - case 981: return "Material_hasColor"; - case 982: return "Material_color"; - case 983: return "Material_setColor"; - case 984: return "Material_hasTexture"; - case 985: return "Material_texture"; - case 986: return "Material_setTexture"; - case 987: return "delete_Material"; - case 988: return "delete_SolidShape"; - case 989: return "SolidShape_clone"; - case 990: return "SolidShape_getName"; - case 991: return "SolidShape_setName"; - case 992: return "SolidShape_isNameValid"; - case 993: return "SolidShape_getLink_H_geometry"; - case 994: return "SolidShape_setLink_H_geometry"; - case 995: return "SolidShape_isMaterialSet"; - case 996: return "SolidShape_getMaterial"; - case 997: return "SolidShape_setMaterial"; - case 998: return "SolidShape_isSphere"; - case 999: return "SolidShape_isBox"; - case 1000: return "SolidShape_isCylinder"; - case 1001: return "SolidShape_isExternalMesh"; - case 1002: return "SolidShape_asSphere"; - case 1003: return "SolidShape_asBox"; - case 1004: return "SolidShape_asCylinder"; - case 1005: return "SolidShape_asExternalMesh"; - case 1006: return "delete_Sphere"; - case 1007: return "Sphere_clone"; - case 1008: return "Sphere_getRadius"; - case 1009: return "Sphere_setRadius"; - case 1010: return "new_Sphere"; - case 1011: return "delete_Box"; - case 1012: return "Box_clone"; - case 1013: return "Box_getX"; - case 1014: return "Box_setX"; - case 1015: return "Box_getY"; - case 1016: return "Box_setY"; - case 1017: return "Box_getZ"; - case 1018: return "Box_setZ"; - case 1019: return "new_Box"; - case 1020: return "delete_Cylinder"; - case 1021: return "Cylinder_clone"; - case 1022: return "Cylinder_getLength"; - case 1023: return "Cylinder_setLength"; - case 1024: return "Cylinder_getRadius"; - case 1025: return "Cylinder_setRadius"; - case 1026: return "new_Cylinder"; - case 1027: return "delete_ExternalMesh"; - case 1028: return "ExternalMesh_clone"; - case 1029: return "ExternalMesh_getFilename"; - case 1030: return "ExternalMesh_getFileLocationOnLocalFileSystem"; - case 1031: return "ExternalMesh_setFilename"; - case 1032: return "ExternalMesh_getScale"; - case 1033: return "ExternalMesh_setScale"; - case 1034: return "new_ExternalMesh"; - case 1035: return "delete_ModelSolidShapes"; - case 1036: return "new_ModelSolidShapes"; - case 1037: return "ModelSolidShapes_clear"; - case 1038: return "ModelSolidShapes_resize"; - case 1039: return "ModelSolidShapes_isConsistent"; - case 1040: return "ModelSolidShapes_getLinkSolidShapes"; - case 1041: return "Neighbor_neighborLink_get"; - case 1042: return "Neighbor_neighborLink_set"; - case 1043: return "Neighbor_neighborJoint_get"; - case 1044: return "Neighbor_neighborJoint_set"; - case 1045: return "new_Neighbor"; - case 1046: return "delete_Neighbor"; - case 1047: return "new_Model"; - case 1048: return "Model_copy"; - case 1049: return "delete_Model"; - case 1050: return "Model_getNrOfLinks"; - case 1051: return "Model_getLinkName"; - case 1052: return "Model_getLinkIndex"; - case 1053: return "Model_isValidLinkIndex"; - case 1054: return "Model_getLink"; - case 1055: return "Model_addLink"; - case 1056: return "Model_getNrOfJoints"; - case 1057: return "Model_getJointName"; - case 1058: return "Model_getTotalMass"; - case 1059: return "Model_getJointIndex"; - case 1060: return "Model_getJoint"; - case 1061: return "Model_isValidJointIndex"; - case 1062: return "Model_isLinkNameUsed"; - case 1063: return "Model_isJointNameUsed"; - case 1064: return "Model_isFrameNameUsed"; - case 1065: return "Model_addJoint"; - case 1066: return "Model_addJointAndLink"; - case 1067: return "Model_insertLinkToExistingJointAndAddJointForDisplacedLink"; - case 1068: return "Model_getNrOfPosCoords"; - case 1069: return "Model_getNrOfDOFs"; - case 1070: return "Model_getNrOfFrames"; - case 1071: return "Model_addAdditionalFrameToLink"; - case 1072: return "Model_getFrameName"; - case 1073: return "Model_getFrameIndex"; - case 1074: return "Model_isValidFrameIndex"; - case 1075: return "Model_getFrameTransform"; - case 1076: return "Model_getFrameLink"; - case 1077: return "Model_getLinkAdditionalFrames"; - case 1078: return "Model_getNrOfNeighbors"; - case 1079: return "Model_getNeighbor"; - case 1080: return "Model_setDefaultBaseLink"; - case 1081: return "Model_getDefaultBaseLink"; - case 1082: return "Model_computeFullTreeTraversal"; - case 1083: return "Model_getInertialParameters"; - case 1084: return "Model_updateInertialParameters"; - case 1085: return "Model_visualSolidShapes"; - case 1086: return "Model_collisionSolidShapes"; - case 1087: return "Model_toString"; - case 1088: return "new_JointPosDoubleArray"; - case 1089: return "JointPosDoubleArray_resize"; - case 1090: return "JointPosDoubleArray_isConsistent"; - case 1091: return "delete_JointPosDoubleArray"; - case 1092: return "new_JointDOFsDoubleArray"; - case 1093: return "JointDOFsDoubleArray_resize"; - case 1094: return "JointDOFsDoubleArray_isConsistent"; - case 1095: return "delete_JointDOFsDoubleArray"; - case 1096: return "new_DOFSpatialForceArray"; - case 1097: return "DOFSpatialForceArray_resize"; - case 1098: return "DOFSpatialForceArray_isConsistent"; - case 1099: return "DOFSpatialForceArray_paren"; - case 1100: return "delete_DOFSpatialForceArray"; - case 1101: return "new_DOFSpatialMotionArray"; - case 1102: return "DOFSpatialMotionArray_resize"; - case 1103: return "DOFSpatialMotionArray_isConsistent"; - case 1104: return "DOFSpatialMotionArray_paren"; - case 1105: return "delete_DOFSpatialMotionArray"; - case 1106: return "new_FrameFreeFloatingJacobian"; - case 1107: return "FrameFreeFloatingJacobian_resize"; - case 1108: return "FrameFreeFloatingJacobian_isConsistent"; - case 1109: return "delete_FrameFreeFloatingJacobian"; - case 1110: return "new_MomentumFreeFloatingJacobian"; - case 1111: return "MomentumFreeFloatingJacobian_resize"; - case 1112: return "MomentumFreeFloatingJacobian_isConsistent"; - case 1113: return "delete_MomentumFreeFloatingJacobian"; - case 1114: return "new_FreeFloatingMassMatrix"; - case 1115: return "FreeFloatingMassMatrix_resize"; - case 1116: return "delete_FreeFloatingMassMatrix"; - case 1117: return "new_FreeFloatingPos"; - case 1118: return "FreeFloatingPos_resize"; - case 1119: return "FreeFloatingPos_worldBasePos"; - case 1120: return "FreeFloatingPos_jointPos"; - case 1121: return "FreeFloatingPos_getNrOfPosCoords"; - case 1122: return "delete_FreeFloatingPos"; - case 1123: return "new_FreeFloatingGeneralizedTorques"; - case 1124: return "FreeFloatingGeneralizedTorques_resize"; - case 1125: return "FreeFloatingGeneralizedTorques_baseWrench"; - case 1126: return "FreeFloatingGeneralizedTorques_jointTorques"; - case 1127: return "FreeFloatingGeneralizedTorques_getNrOfDOFs"; - case 1128: return "delete_FreeFloatingGeneralizedTorques"; - case 1129: return "new_FreeFloatingVel"; - case 1130: return "FreeFloatingVel_resize"; - case 1131: return "FreeFloatingVel_baseVel"; - case 1132: return "FreeFloatingVel_jointVel"; - case 1133: return "FreeFloatingVel_getNrOfDOFs"; - case 1134: return "delete_FreeFloatingVel"; - case 1135: return "new_FreeFloatingAcc"; - case 1136: return "FreeFloatingAcc_resize"; - case 1137: return "FreeFloatingAcc_baseAcc"; - case 1138: return "FreeFloatingAcc_jointAcc"; - case 1139: return "FreeFloatingAcc_getNrOfDOFs"; - case 1140: return "delete_FreeFloatingAcc"; - case 1141: return "ContactWrench_contactId"; - case 1142: return "ContactWrench_contactPoint"; - case 1143: return "ContactWrench_contactWrench"; - case 1144: return "new_ContactWrench"; - case 1145: return "delete_ContactWrench"; - case 1146: return "new_LinkContactWrenches"; - case 1147: return "LinkContactWrenches_resize"; - case 1148: return "LinkContactWrenches_getNrOfContactsForLink"; - case 1149: return "LinkContactWrenches_setNrOfContactsForLink"; - case 1150: return "LinkContactWrenches_getNrOfLinks"; - case 1151: return "LinkContactWrenches_contactWrench"; - case 1152: return "LinkContactWrenches_computeNetWrenches"; - case 1153: return "LinkContactWrenches_toString"; - case 1154: return "delete_LinkContactWrenches"; - case 1155: return "_wrap_getRandomLink"; - case 1156: return "_wrap_addRandomLinkToModel"; - case 1157: return "_wrap_addRandomAdditionalFrameToModel"; - case 1158: return "_wrap_getRandomLinkIndexOfModel"; - case 1159: return "_wrap_getRandomLinkOfModel"; - case 1160: return "_wrap_int2string"; - case 1161: return "_wrap_getRandomModel"; - case 1162: return "_wrap_getRandomChain"; - case 1163: return "_wrap_getRandomJointPositions"; - case 1164: return "_wrap_getRandomInverseDynamicsInputs"; - case 1165: return "_wrap_removeFakeLinks"; - case 1166: return "_wrap_createReducedModel"; - case 1167: return "_wrap_createModelWithNormalizedJointNumbering"; - case 1168: return "_wrap_extractSubModel"; - case 1169: return "new_SubModelDecomposition"; - case 1170: return "delete_SubModelDecomposition"; - case 1171: return "SubModelDecomposition_splitModelAlongJoints"; - case 1172: return "SubModelDecomposition_setNrOfSubModels"; - case 1173: return "SubModelDecomposition_getNrOfSubModels"; - case 1174: return "SubModelDecomposition_getNrOfLinks"; - case 1175: return "SubModelDecomposition_getTraversal"; - case 1176: return "SubModelDecomposition_getSubModelOfLink"; - case 1177: return "SubModelDecomposition_getSubModelOfFrame"; - case 1178: return "_wrap_computeTransformToTraversalBase"; - case 1179: return "_wrap_computeTransformToSubModelBase"; - case 1180: return "SolidShapesVector_pop"; - case 1181: return "SolidShapesVector_brace"; - case 1182: return "SolidShapesVector_setbrace"; - case 1183: return "SolidShapesVector_append"; - case 1184: return "SolidShapesVector_empty"; - case 1185: return "SolidShapesVector_size"; - case 1186: return "SolidShapesVector_swap"; - case 1187: return "SolidShapesVector_begin"; - case 1188: return "SolidShapesVector_end"; - case 1189: return "SolidShapesVector_rbegin"; - case 1190: return "SolidShapesVector_rend"; - case 1191: return "SolidShapesVector_clear"; - case 1192: return "SolidShapesVector_get_allocator"; - case 1193: return "SolidShapesVector_pop_back"; - case 1194: return "SolidShapesVector_erase"; - case 1195: return "new_SolidShapesVector"; - case 1196: return "SolidShapesVector_push_back"; - case 1197: return "SolidShapesVector_front"; - case 1198: return "SolidShapesVector_back"; - case 1199: return "SolidShapesVector_assign"; - case 1200: return "SolidShapesVector_resize"; - case 1201: return "SolidShapesVector_insert"; - case 1202: return "SolidShapesVector_reserve"; - case 1203: return "SolidShapesVector_capacity"; - case 1204: return "delete_SolidShapesVector"; - case 1205: return "LinksSolidShapesVector_pop"; - case 1206: return "LinksSolidShapesVector_brace"; - case 1207: return "LinksSolidShapesVector_setbrace"; - case 1208: return "LinksSolidShapesVector_append"; - case 1209: return "LinksSolidShapesVector_empty"; - case 1210: return "LinksSolidShapesVector_size"; - case 1211: return "LinksSolidShapesVector_swap"; - case 1212: return "LinksSolidShapesVector_begin"; - case 1213: return "LinksSolidShapesVector_end"; - case 1214: return "LinksSolidShapesVector_rbegin"; - case 1215: return "LinksSolidShapesVector_rend"; - case 1216: return "LinksSolidShapesVector_clear"; - case 1217: return "LinksSolidShapesVector_get_allocator"; - case 1218: return "LinksSolidShapesVector_pop_back"; - case 1219: return "LinksSolidShapesVector_erase"; - case 1220: return "new_LinksSolidShapesVector"; - case 1221: return "LinksSolidShapesVector_push_back"; - case 1222: return "LinksSolidShapesVector_front"; - case 1223: return "LinksSolidShapesVector_back"; - case 1224: return "LinksSolidShapesVector_assign"; - case 1225: return "LinksSolidShapesVector_resize"; - case 1226: return "LinksSolidShapesVector_insert"; - case 1227: return "LinksSolidShapesVector_reserve"; - case 1228: return "LinksSolidShapesVector_capacity"; - case 1229: return "delete_LinksSolidShapesVector"; - case 1230: return "_wrap_ForwardPositionKinematics"; - case 1231: return "_wrap_ForwardVelAccKinematics"; - case 1232: return "_wrap_ForwardPosVelAccKinematics"; - case 1233: return "_wrap_ForwardPosVelKinematics"; - case 1234: return "_wrap_ForwardAccKinematics"; - case 1235: return "_wrap_ForwardBiasAccKinematics"; - case 1236: return "_wrap_ComputeLinearAndAngularMomentum"; - case 1237: return "_wrap_ComputeLinearAndAngularMomentumDerivativeBias"; - case 1238: return "_wrap_RNEADynamicPhase"; - case 1239: return "_wrap_CompositeRigidBodyAlgorithm"; - case 1240: return "new_ArticulatedBodyAlgorithmInternalBuffers"; - case 1241: return "ArticulatedBodyAlgorithmInternalBuffers_resize"; - case 1242: return "ArticulatedBodyAlgorithmInternalBuffers_isConsistent"; - case 1243: return "ArticulatedBodyAlgorithmInternalBuffers_S_get"; - case 1244: return "ArticulatedBodyAlgorithmInternalBuffers_S_set"; - case 1245: return "ArticulatedBodyAlgorithmInternalBuffers_U_get"; - case 1246: return "ArticulatedBodyAlgorithmInternalBuffers_U_set"; - case 1247: return "ArticulatedBodyAlgorithmInternalBuffers_D_get"; - case 1248: return "ArticulatedBodyAlgorithmInternalBuffers_D_set"; - case 1249: return "ArticulatedBodyAlgorithmInternalBuffers_u_get"; - case 1250: return "ArticulatedBodyAlgorithmInternalBuffers_u_set"; - case 1251: return "ArticulatedBodyAlgorithmInternalBuffers_linksVel_get"; - case 1252: return "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set"; - case 1253: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get"; - case 1254: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set"; - case 1255: return "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get"; - case 1256: return "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set"; - case 1257: return "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get"; - case 1258: return "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set"; - case 1259: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get"; - case 1260: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set"; - case 1261: return "delete_ArticulatedBodyAlgorithmInternalBuffers"; - case 1262: return "_wrap_ArticulatedBodyAlgorithm"; - case 1263: return "_wrap_InverseDynamicsInertialParametersRegressor"; - case 1264: return "DHLink_A_get"; - case 1265: return "DHLink_A_set"; - case 1266: return "DHLink_D_get"; - case 1267: return "DHLink_D_set"; - case 1268: return "DHLink_Alpha_get"; - case 1269: return "DHLink_Alpha_set"; - case 1270: return "DHLink_Offset_get"; - case 1271: return "DHLink_Offset_set"; - case 1272: return "DHLink_Min_get"; - case 1273: return "DHLink_Min_set"; - case 1274: return "DHLink_Max_get"; - case 1275: return "DHLink_Max_set"; - case 1276: return "new_DHLink"; - case 1277: return "delete_DHLink"; - case 1278: return "DHChain_setNrOfDOFs"; - case 1279: return "DHChain_getNrOfDOFs"; - case 1280: return "DHChain_setH0"; - case 1281: return "DHChain_getH0"; - case 1282: return "DHChain_setHN"; - case 1283: return "DHChain_getHN"; - case 1284: return "DHChain_paren"; - case 1285: return "DHChain_getDOFName"; - case 1286: return "DHChain_setDOFName"; - case 1287: return "DHChain_toModel"; - case 1288: return "DHChain_fromModel"; - case 1289: return "new_DHChain"; - case 1290: return "delete_DHChain"; - case 1291: return "_wrap_TransformFromDHCraig1989"; - case 1292: return "_wrap_TransformFromDH"; - case 1293: return "_wrap_ExtractDHChainFromModel"; - case 1294: return "_wrap_CreateModelFromDHChain"; - case 1295: return "NR_OF_SENSOR_TYPES_get"; - case 1296: return "_wrap_isLinkSensor"; - case 1297: return "_wrap_isJointSensor"; - case 1298: return "_wrap_getSensorTypeSize"; - case 1299: return "delete_Sensor"; - case 1300: return "Sensor_getName"; - case 1301: return "Sensor_getSensorType"; - case 1302: return "Sensor_isValid"; - case 1303: return "Sensor_setName"; - case 1304: return "Sensor_clone"; - case 1305: return "Sensor_isConsistent"; - case 1306: return "Sensor_updateIndices"; - case 1307: return "delete_JointSensor"; - case 1308: return "JointSensor_getParentJoint"; - case 1309: return "JointSensor_getParentJointIndex"; - case 1310: return "JointSensor_setParentJoint"; - case 1311: return "JointSensor_setParentJointIndex"; - case 1312: return "JointSensor_isConsistent"; - case 1313: return "delete_LinkSensor"; - case 1314: return "LinkSensor_getParentLink"; - case 1315: return "LinkSensor_getParentLinkIndex"; - case 1316: return "LinkSensor_getLinkSensorTransform"; - case 1317: return "LinkSensor_setParentLink"; - case 1318: return "LinkSensor_setParentLinkIndex"; - case 1319: return "LinkSensor_setLinkSensorTransform"; - case 1320: return "LinkSensor_isConsistent"; - case 1321: return "new_SensorsList"; - case 1322: return "delete_SensorsList"; - case 1323: return "SensorsList_addSensor"; - case 1324: return "SensorsList_setSerialization"; - case 1325: return "SensorsList_getSerialization"; - case 1326: return "SensorsList_getNrOfSensors"; - case 1327: return "SensorsList_getSensorIndex"; - case 1328: return "SensorsList_getSizeOfAllSensorsMeasurements"; - case 1329: return "SensorsList_getSensor"; - case 1330: return "SensorsList_isConsistent"; - case 1331: return "SensorsList_removeSensor"; - case 1332: return "SensorsList_removeAllSensorsOfType"; - case 1333: return "SensorsList_getSixAxisForceTorqueSensor"; - case 1334: return "SensorsList_getAccelerometerSensor"; - case 1335: return "SensorsList_getGyroscopeSensor"; - case 1336: return "SensorsList_getThreeAxisAngularAccelerometerSensor"; - case 1337: return "SensorsList_getThreeAxisForceTorqueContactSensor"; - case 1338: return "new_SensorsMeasurements"; - case 1339: return "delete_SensorsMeasurements"; - case 1340: return "SensorsMeasurements_setNrOfSensors"; - case 1341: return "SensorsMeasurements_getNrOfSensors"; - case 1342: return "SensorsMeasurements_resize"; - case 1343: return "SensorsMeasurements_toVector"; - case 1344: return "SensorsMeasurements_setMeasurement"; - case 1345: return "SensorsMeasurements_getMeasurement"; - case 1346: return "SensorsMeasurements_getSizeOfAllSensorsMeasurements"; - case 1347: return "new_SixAxisForceTorqueSensor"; - case 1348: return "delete_SixAxisForceTorqueSensor"; - case 1349: return "SixAxisForceTorqueSensor_setName"; - case 1350: return "SixAxisForceTorqueSensor_setFirstLinkSensorTransform"; - case 1351: return "SixAxisForceTorqueSensor_setSecondLinkSensorTransform"; - case 1352: return "SixAxisForceTorqueSensor_getFirstLinkIndex"; - case 1353: return "SixAxisForceTorqueSensor_getSecondLinkIndex"; - case 1354: return "SixAxisForceTorqueSensor_setFirstLinkName"; - case 1355: return "SixAxisForceTorqueSensor_setSecondLinkName"; - case 1356: return "SixAxisForceTorqueSensor_getFirstLinkName"; - case 1357: return "SixAxisForceTorqueSensor_getSecondLinkName"; - case 1358: return "SixAxisForceTorqueSensor_setParentJoint"; - case 1359: return "SixAxisForceTorqueSensor_setParentJointIndex"; - case 1360: return "SixAxisForceTorqueSensor_setAppliedWrenchLink"; - case 1361: return "SixAxisForceTorqueSensor_getName"; - case 1362: return "SixAxisForceTorqueSensor_getSensorType"; - case 1363: return "SixAxisForceTorqueSensor_getParentJoint"; - case 1364: return "SixAxisForceTorqueSensor_getParentJointIndex"; - case 1365: return "SixAxisForceTorqueSensor_isValid"; - case 1366: return "SixAxisForceTorqueSensor_clone"; - case 1367: return "SixAxisForceTorqueSensor_updateIndices"; - case 1368: return "SixAxisForceTorqueSensor_getAppliedWrenchLink"; - case 1369: return "SixAxisForceTorqueSensor_isLinkAttachedToSensor"; - case 1370: return "SixAxisForceTorqueSensor_getLinkSensorTransform"; - case 1371: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLink"; - case 1372: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix"; - case 1373: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix"; - case 1374: return "SixAxisForceTorqueSensor_predictMeasurement"; - case 1375: return "SixAxisForceTorqueSensor_toString"; - case 1376: return "new_AccelerometerSensor"; - case 1377: return "delete_AccelerometerSensor"; - case 1378: return "AccelerometerSensor_setName"; - case 1379: return "AccelerometerSensor_setLinkSensorTransform"; - case 1380: return "AccelerometerSensor_setParentLink"; - case 1381: return "AccelerometerSensor_setParentLinkIndex"; - case 1382: return "AccelerometerSensor_getName"; - case 1383: return "AccelerometerSensor_getSensorType"; - case 1384: return "AccelerometerSensor_getParentLink"; - case 1385: return "AccelerometerSensor_getParentLinkIndex"; - case 1386: return "AccelerometerSensor_getLinkSensorTransform"; - case 1387: return "AccelerometerSensor_isValid"; - case 1388: return "AccelerometerSensor_clone"; - case 1389: return "AccelerometerSensor_updateIndices"; - case 1390: return "AccelerometerSensor_predictMeasurement"; - case 1391: return "new_GyroscopeSensor"; - case 1392: return "delete_GyroscopeSensor"; - case 1393: return "GyroscopeSensor_setName"; - case 1394: return "GyroscopeSensor_setLinkSensorTransform"; - case 1395: return "GyroscopeSensor_setParentLink"; - case 1396: return "GyroscopeSensor_setParentLinkIndex"; - case 1397: return "GyroscopeSensor_getName"; - case 1398: return "GyroscopeSensor_getSensorType"; - case 1399: return "GyroscopeSensor_getParentLink"; - case 1400: return "GyroscopeSensor_getParentLinkIndex"; - case 1401: return "GyroscopeSensor_getLinkSensorTransform"; - case 1402: return "GyroscopeSensor_isValid"; - case 1403: return "GyroscopeSensor_clone"; - case 1404: return "GyroscopeSensor_updateIndices"; - case 1405: return "GyroscopeSensor_predictMeasurement"; - case 1406: return "new_ThreeAxisAngularAccelerometerSensor"; - case 1407: return "delete_ThreeAxisAngularAccelerometerSensor"; - case 1408: return "ThreeAxisAngularAccelerometerSensor_setName"; - case 1409: return "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform"; - case 1410: return "ThreeAxisAngularAccelerometerSensor_setParentLink"; - case 1411: return "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex"; - case 1412: return "ThreeAxisAngularAccelerometerSensor_getName"; - case 1413: return "ThreeAxisAngularAccelerometerSensor_getSensorType"; - case 1414: return "ThreeAxisAngularAccelerometerSensor_getParentLink"; - case 1415: return "ThreeAxisAngularAccelerometerSensor_getParentLinkIndex"; - case 1416: return "ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform"; - case 1417: return "ThreeAxisAngularAccelerometerSensor_isValid"; - case 1418: return "ThreeAxisAngularAccelerometerSensor_clone"; - case 1419: return "ThreeAxisAngularAccelerometerSensor_updateIndices"; - case 1420: return "ThreeAxisAngularAccelerometerSensor_predictMeasurement"; - case 1421: return "new_ThreeAxisForceTorqueContactSensor"; - case 1422: return "delete_ThreeAxisForceTorqueContactSensor"; - case 1423: return "ThreeAxisForceTorqueContactSensor_setName"; - case 1424: return "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform"; - case 1425: return "ThreeAxisForceTorqueContactSensor_setParentLink"; - case 1426: return "ThreeAxisForceTorqueContactSensor_setParentLinkIndex"; - case 1427: return "ThreeAxisForceTorqueContactSensor_getName"; - case 1428: return "ThreeAxisForceTorqueContactSensor_getSensorType"; - case 1429: return "ThreeAxisForceTorqueContactSensor_getParentLink"; - case 1430: return "ThreeAxisForceTorqueContactSensor_getParentLinkIndex"; - case 1431: return "ThreeAxisForceTorqueContactSensor_getLinkSensorTransform"; - case 1432: return "ThreeAxisForceTorqueContactSensor_isValid"; - case 1433: return "ThreeAxisForceTorqueContactSensor_clone"; - case 1434: return "ThreeAxisForceTorqueContactSensor_updateIndices"; - case 1435: return "ThreeAxisForceTorqueContactSensor_setLoadCellLocations"; - case 1436: return "ThreeAxisForceTorqueContactSensor_getLoadCellLocations"; - case 1437: return "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements"; - case 1438: return "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements"; - case 1439: return "_wrap_predictSensorsMeasurements"; - case 1440: return "_wrap_predictSensorsMeasurementsFromRawBuffers"; - case 1441: return "_wrap_dofsListFromURDF"; - case 1442: return "_wrap_dofsListFromURDFString"; - case 1443: return "ModelParserOptions_addSensorFramesAsAdditionalFrames_get"; - case 1444: return "ModelParserOptions_addSensorFramesAsAdditionalFrames_set"; - case 1445: return "ModelParserOptions_originalFilename_get"; - case 1446: return "ModelParserOptions_originalFilename_set"; - case 1447: return "new_ModelParserOptions"; - case 1448: return "delete_ModelParserOptions"; - case 1449: return "new_ModelLoader"; - case 1450: return "delete_ModelLoader"; - case 1451: return "ModelLoader_parsingOptions"; - case 1452: return "ModelLoader_setParsingOptions"; - case 1453: return "ModelLoader_loadModelFromString"; - case 1454: return "ModelLoader_loadModelFromFile"; - case 1455: return "ModelLoader_loadReducedModelFromFullModel"; - case 1456: return "ModelLoader_loadReducedModelFromString"; - case 1457: return "ModelLoader_loadReducedModelFromFile"; - case 1458: return "ModelLoader_model"; - case 1459: return "ModelLoader_sensors"; - case 1460: return "ModelLoader_isValid"; - case 1461: return "ModelExporterOptions_baseLink_get"; - case 1462: return "ModelExporterOptions_baseLink_set"; - case 1463: return "ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_get"; - case 1464: return "ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_set"; - case 1465: return "ModelExporterOptions_robotExportedName_get"; - case 1466: return "ModelExporterOptions_robotExportedName_set"; - case 1467: return "new_ModelExporterOptions"; - case 1468: return "delete_ModelExporterOptions"; - case 1469: return "new_ModelExporter"; - case 1470: return "delete_ModelExporter"; - case 1471: return "ModelExporter_exportingOptions"; - case 1472: return "ModelExporter_setExportingOptions"; - case 1473: return "ModelExporter_init"; - case 1474: return "ModelExporter_model"; - case 1475: return "ModelExporter_sensors"; - case 1476: return "ModelExporter_isValid"; - case 1477: return "ModelExporter_exportModelToString"; - case 1478: return "ModelExporter_exportModelToFile"; - case 1479: return "new_ModelCalibrationHelper"; - case 1480: return "delete_ModelCalibrationHelper"; - case 1481: return "ModelCalibrationHelper_loadModelFromString"; - case 1482: return "ModelCalibrationHelper_loadModelFromFile"; - case 1483: return "ModelCalibrationHelper_updateModelInertialParametersToString"; - case 1484: return "ModelCalibrationHelper_updateModelInertialParametersToFile"; - case 1485: return "ModelCalibrationHelper_model"; - case 1486: return "ModelCalibrationHelper_sensors"; - case 1487: return "ModelCalibrationHelper_isValid"; - case 1488: return "new_UnknownWrenchContact"; - case 1489: return "UnknownWrenchContact_unknownType_get"; - case 1490: return "UnknownWrenchContact_unknownType_set"; - case 1491: return "UnknownWrenchContact_contactPoint_get"; - case 1492: return "UnknownWrenchContact_contactPoint_set"; - case 1493: return "UnknownWrenchContact_forceDirection_get"; - case 1494: return "UnknownWrenchContact_forceDirection_set"; - case 1495: return "UnknownWrenchContact_knownWrench_get"; - case 1496: return "UnknownWrenchContact_knownWrench_set"; - case 1497: return "UnknownWrenchContact_contactId_get"; - case 1498: return "UnknownWrenchContact_contactId_set"; - case 1499: return "delete_UnknownWrenchContact"; - case 1500: return "new_LinkUnknownWrenchContacts"; - case 1501: return "LinkUnknownWrenchContacts_clear"; - case 1502: return "LinkUnknownWrenchContacts_resize"; - case 1503: return "LinkUnknownWrenchContacts_getNrOfContactsForLink"; - case 1504: return "LinkUnknownWrenchContacts_setNrOfContactsForLink"; - case 1505: return "LinkUnknownWrenchContacts_addNewContactForLink"; - case 1506: return "LinkUnknownWrenchContacts_addNewContactInFrame"; - case 1507: return "LinkUnknownWrenchContacts_addNewUnknownFullWrenchInFrameOrigin"; - case 1508: return "LinkUnknownWrenchContacts_contactWrench"; - case 1509: return "LinkUnknownWrenchContacts_toString"; - case 1510: return "delete_LinkUnknownWrenchContacts"; - case 1511: return "new_estimateExternalWrenchesBuffers"; - case 1512: return "estimateExternalWrenchesBuffers_resize"; - case 1513: return "estimateExternalWrenchesBuffers_getNrOfSubModels"; - case 1514: return "estimateExternalWrenchesBuffers_getNrOfLinks"; - case 1515: return "estimateExternalWrenchesBuffers_isConsistent"; - case 1516: return "estimateExternalWrenchesBuffers_A_get"; - case 1517: return "estimateExternalWrenchesBuffers_A_set"; - case 1518: return "estimateExternalWrenchesBuffers_x_get"; - case 1519: return "estimateExternalWrenchesBuffers_x_set"; - case 1520: return "estimateExternalWrenchesBuffers_b_get"; - case 1521: return "estimateExternalWrenchesBuffers_b_set"; - case 1522: return "estimateExternalWrenchesBuffers_b_contacts_subtree_get"; - case 1523: return "estimateExternalWrenchesBuffers_b_contacts_subtree_set"; - case 1524: return "estimateExternalWrenchesBuffers_subModelBase_H_link_get"; - case 1525: return "estimateExternalWrenchesBuffers_subModelBase_H_link_set"; - case 1526: return "delete_estimateExternalWrenchesBuffers"; - case 1527: return "_wrap_estimateExternalWrenchesWithoutInternalFT"; - case 1528: return "_wrap_estimateExternalWrenches"; - case 1529: return "_wrap_dynamicsEstimationForwardVelAccKinematics"; - case 1530: return "_wrap_dynamicsEstimationForwardVelKinematics"; - case 1531: return "_wrap_computeLinkNetWrenchesWithoutGravity"; - case 1532: return "_wrap_estimateLinkContactWrenchesFromLinkNetExternalWrenches"; - case 1533: return "new_ExtWrenchesAndJointTorquesEstimator"; - case 1534: return "delete_ExtWrenchesAndJointTorquesEstimator"; - case 1535: return "ExtWrenchesAndJointTorquesEstimator_setModelAndSensors"; - case 1536: return "ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFile"; - case 1537: return "ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFileWithSpecifiedDOFs"; - case 1538: return "ExtWrenchesAndJointTorquesEstimator_model"; - case 1539: return "ExtWrenchesAndJointTorquesEstimator_sensors"; - case 1540: return "ExtWrenchesAndJointTorquesEstimator_submodels"; - case 1541: return "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase"; - case 1542: return "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase"; - case 1543: return "ExtWrenchesAndJointTorquesEstimator_computeExpectedFTSensorsMeasurements"; - case 1544: return "ExtWrenchesAndJointTorquesEstimator_estimateExtWrenchesAndJointTorques"; - case 1545: return "ExtWrenchesAndJointTorquesEstimator_checkThatTheModelIsStill"; - case 1546: return "ExtWrenchesAndJointTorquesEstimator_estimateLinkNetWrenchesWithoutGravity"; - case 1547: return "new_SimpleLeggedOdometry"; - case 1548: return "delete_SimpleLeggedOdometry"; - case 1549: return "SimpleLeggedOdometry_setModel"; - case 1550: return "SimpleLeggedOdometry_model"; - case 1551: return "SimpleLeggedOdometry_updateKinematics"; - case 1552: return "SimpleLeggedOdometry_init"; - case 1553: return "SimpleLeggedOdometry_changeFixedFrame"; - case 1554: return "SimpleLeggedOdometry_getCurrentFixedLink"; - case 1555: return "SimpleLeggedOdometry_getWorldLinkTransform"; - case 1556: return "SimpleLeggedOdometry_getWorldFrameTransform"; - case 1557: return "_wrap_isLinkBerdyDynamicVariable"; - case 1558: return "_wrap_isJointBerdyDynamicVariable"; - case 1559: return "_wrap_isDOFBerdyDynamicVariable"; - case 1560: return "new_BerdyOptions"; - case 1561: return "BerdyOptions_berdyVariant_get"; - case 1562: return "BerdyOptions_berdyVariant_set"; - case 1563: return "BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_get"; - case 1564: return "BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_set"; - case 1565: return "BerdyOptions_includeAllJointAccelerationsAsSensors_get"; - case 1566: return "BerdyOptions_includeAllJointAccelerationsAsSensors_set"; - case 1567: return "BerdyOptions_includeAllJointTorquesAsSensors_get"; - case 1568: return "BerdyOptions_includeAllJointTorquesAsSensors_set"; - case 1569: return "BerdyOptions_includeAllNetExternalWrenchesAsSensors_get"; - case 1570: return "BerdyOptions_includeAllNetExternalWrenchesAsSensors_set"; - case 1571: return "BerdyOptions_includeFixedBaseExternalWrench_get"; - case 1572: return "BerdyOptions_includeFixedBaseExternalWrench_set"; - case 1573: return "BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_get"; - case 1574: return "BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_set"; - case 1575: return "BerdyOptions_baseLink_get"; - case 1576: return "BerdyOptions_baseLink_set"; - case 1577: return "BerdyOptions_checkConsistency"; - case 1578: return "delete_BerdyOptions"; - case 1579: return "BerdySensor_type_get"; - case 1580: return "BerdySensor_type_set"; - case 1581: return "BerdySensor_id_get"; - case 1582: return "BerdySensor_id_set"; - case 1583: return "BerdySensor_range_get"; - case 1584: return "BerdySensor_range_set"; - case 1585: return "BerdySensor_eq"; - case 1586: return "BerdySensor_lt"; - case 1587: return "new_BerdySensor"; - case 1588: return "delete_BerdySensor"; - case 1589: return "BerdyDynamicVariable_type_get"; - case 1590: return "BerdyDynamicVariable_type_set"; - case 1591: return "BerdyDynamicVariable_id_get"; - case 1592: return "BerdyDynamicVariable_id_set"; - case 1593: return "BerdyDynamicVariable_range_get"; - case 1594: return "BerdyDynamicVariable_range_set"; - case 1595: return "BerdyDynamicVariable_eq"; - case 1596: return "BerdyDynamicVariable_lt"; - case 1597: return "new_BerdyDynamicVariable"; - case 1598: return "delete_BerdyDynamicVariable"; - case 1599: return "new_BerdyHelper"; - case 1600: return "BerdyHelper_dynamicTraversal"; - case 1601: return "BerdyHelper_model"; - case 1602: return "BerdyHelper_sensors"; - case 1603: return "BerdyHelper_isValid"; - case 1604: return "BerdyHelper_init"; - case 1605: return "BerdyHelper_getOptions"; - case 1606: return "BerdyHelper_getNrOfDynamicVariables"; - case 1607: return "BerdyHelper_getNrOfDynamicEquations"; - case 1608: return "BerdyHelper_getNrOfSensorsMeasurements"; - case 1609: return "BerdyHelper_resizeAndZeroBerdyMatrices"; - case 1610: return "BerdyHelper_getBerdyMatrices"; - case 1611: return "BerdyHelper_getSensorsOrdering"; - case 1612: return "BerdyHelper_getRangeSensorVariable"; - case 1613: return "BerdyHelper_getRangeDOFSensorVariable"; - case 1614: return "BerdyHelper_getRangeJointSensorVariable"; - case 1615: return "BerdyHelper_getRangeLinkSensorVariable"; - case 1616: return "BerdyHelper_getRangeRCMSensorVariable"; - case 1617: return "BerdyHelper_getRangeLinkVariable"; - case 1618: return "BerdyHelper_getRangeJointVariable"; - case 1619: return "BerdyHelper_getRangeDOFVariable"; - case 1620: return "BerdyHelper_getDynamicVariablesOrdering"; - case 1621: return "BerdyHelper_serializeDynamicVariables"; - case 1622: return "BerdyHelper_serializeSensorVariables"; - case 1623: return "BerdyHelper_serializeDynamicVariablesComputedFromFixedBaseRNEA"; - case 1624: return "BerdyHelper_extractJointTorquesFromDynamicVariables"; - case 1625: return "BerdyHelper_extractLinkNetExternalWrenchesFromDynamicVariables"; - case 1626: return "BerdyHelper_updateKinematicsFromFloatingBase"; - case 1627: return "BerdyHelper_updateKinematicsFromFixedBase"; - case 1628: return "BerdyHelper_updateKinematicsFromTraversalFixedBase"; - case 1629: return "BerdyHelper_setNetExternalWrenchMeasurementFrame"; - case 1630: return "BerdyHelper_getNetExternalWrenchMeasurementFrame"; - case 1631: return "delete_BerdyHelper"; - case 1632: return "new_BerdySparseMAPSolver"; - case 1633: return "delete_BerdySparseMAPSolver"; - case 1634: return "BerdySparseMAPSolver_setDynamicsConstraintsPriorCovariance"; - case 1635: return "BerdySparseMAPSolver_setDynamicsRegularizationPriorCovariance"; - case 1636: return "BerdySparseMAPSolver_setDynamicsRegularizationPriorExpectedValue"; - case 1637: return "BerdySparseMAPSolver_setMeasurementsPriorCovariance"; - case 1638: return "BerdySparseMAPSolver_dynamicsConstraintsPriorCovarianceInverse"; - case 1639: return "BerdySparseMAPSolver_dynamicsRegularizationPriorCovarianceInverse"; - case 1640: return "BerdySparseMAPSolver_dynamicsRegularizationPriorExpectedValue"; - case 1641: return "BerdySparseMAPSolver_measurementsPriorCovarianceInverse"; - case 1642: return "BerdySparseMAPSolver_isValid"; - case 1643: return "BerdySparseMAPSolver_initialize"; - case 1644: return "BerdySparseMAPSolver_updateEstimateInformationFixedBase"; - case 1645: return "BerdySparseMAPSolver_updateEstimateInformationFloatingBase"; - case 1646: return "BerdySparseMAPSolver_doEstimate"; - case 1647: return "BerdySparseMAPSolver_getLastEstimate"; - case 1648: return "AttitudeEstimatorState_m_orientation_get"; - case 1649: return "AttitudeEstimatorState_m_orientation_set"; - case 1650: return "AttitudeEstimatorState_m_angular_velocity_get"; - case 1651: return "AttitudeEstimatorState_m_angular_velocity_set"; - case 1652: return "AttitudeEstimatorState_m_gyroscope_bias_get"; - case 1653: return "AttitudeEstimatorState_m_gyroscope_bias_set"; - case 1654: return "new_AttitudeEstimatorState"; - case 1655: return "delete_AttitudeEstimatorState"; - case 1656: return "delete_IAttitudeEstimator"; - case 1657: return "IAttitudeEstimator_updateFilterWithMeasurements"; - case 1658: return "IAttitudeEstimator_propagateStates"; - case 1659: return "IAttitudeEstimator_getOrientationEstimateAsRotationMatrix"; - case 1660: return "IAttitudeEstimator_getOrientationEstimateAsQuaternion"; - case 1661: return "IAttitudeEstimator_getOrientationEstimateAsRPY"; - case 1662: return "IAttitudeEstimator_getInternalStateSize"; - case 1663: return "IAttitudeEstimator_getInternalState"; - case 1664: return "IAttitudeEstimator_getDefaultInternalInitialState"; - case 1665: return "IAttitudeEstimator_setInternalState"; - case 1666: return "IAttitudeEstimator_setInternalStateInitialOrientation"; - case 1667: return "AttitudeMahonyFilterParameters_time_step_in_seconds_get"; - case 1668: return "AttitudeMahonyFilterParameters_time_step_in_seconds_set"; - case 1669: return "AttitudeMahonyFilterParameters_kp_get"; - case 1670: return "AttitudeMahonyFilterParameters_kp_set"; - case 1671: return "AttitudeMahonyFilterParameters_ki_get"; - case 1672: return "AttitudeMahonyFilterParameters_ki_set"; - case 1673: return "AttitudeMahonyFilterParameters_use_magnetometer_measurements_get"; - case 1674: return "AttitudeMahonyFilterParameters_use_magnetometer_measurements_set"; - case 1675: return "AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_get"; - case 1676: return "AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_set"; - case 1677: return "new_AttitudeMahonyFilterParameters"; - case 1678: return "delete_AttitudeMahonyFilterParameters"; - case 1679: return "new_AttitudeMahonyFilter"; - case 1680: return "AttitudeMahonyFilter_useMagnetoMeterMeasurements"; - case 1681: return "AttitudeMahonyFilter_setConfidenceForMagnetometerMeasurements"; - case 1682: return "AttitudeMahonyFilter_setGainkp"; - case 1683: return "AttitudeMahonyFilter_setGainki"; - case 1684: return "AttitudeMahonyFilter_setTimeStepInSeconds"; - case 1685: return "AttitudeMahonyFilter_setGravityDirection"; - case 1686: return "AttitudeMahonyFilter_setParameters"; - case 1687: return "AttitudeMahonyFilter_getParameters"; - case 1688: return "AttitudeMahonyFilter_updateFilterWithMeasurements"; - case 1689: return "AttitudeMahonyFilter_propagateStates"; - case 1690: return "AttitudeMahonyFilter_getOrientationEstimateAsRotationMatrix"; - case 1691: return "AttitudeMahonyFilter_getOrientationEstimateAsQuaternion"; - case 1692: return "AttitudeMahonyFilter_getOrientationEstimateAsRPY"; - case 1693: return "AttitudeMahonyFilter_getInternalStateSize"; - case 1694: return "AttitudeMahonyFilter_getInternalState"; - case 1695: return "AttitudeMahonyFilter_getDefaultInternalInitialState"; - case 1696: return "AttitudeMahonyFilter_setInternalState"; - case 1697: return "AttitudeMahonyFilter_setInternalStateInitialOrientation"; - case 1698: return "delete_AttitudeMahonyFilter"; - case 1699: return "DiscreteExtendedKalmanFilterHelper_ekf_f"; - case 1700: return "DiscreteExtendedKalmanFilterHelper_ekf_h"; - case 1701: return "DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianF"; - case 1702: return "DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianH"; - case 1703: return "DiscreteExtendedKalmanFilterHelper_ekfPredict"; - case 1704: return "DiscreteExtendedKalmanFilterHelper_ekfUpdate"; - case 1705: return "DiscreteExtendedKalmanFilterHelper_ekfInit"; - case 1706: return "DiscreteExtendedKalmanFilterHelper_ekfReset"; - case 1707: return "DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementVector"; - case 1708: return "DiscreteExtendedKalmanFilterHelper_ekfSetInputVector"; - case 1709: return "DiscreteExtendedKalmanFilterHelper_ekfSetInitialState"; - case 1710: return "DiscreteExtendedKalmanFilterHelper_ekfSetStateCovariance"; - case 1711: return "DiscreteExtendedKalmanFilterHelper_ekfSetSystemNoiseCovariance"; - case 1712: return "DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementNoiseCovariance"; - case 1713: return "DiscreteExtendedKalmanFilterHelper_ekfSetStateSize"; - case 1714: return "DiscreteExtendedKalmanFilterHelper_ekfSetInputSize"; - case 1715: return "DiscreteExtendedKalmanFilterHelper_ekfSetOutputSize"; - case 1716: return "DiscreteExtendedKalmanFilterHelper_ekfGetStates"; - case 1717: return "DiscreteExtendedKalmanFilterHelper_ekfGetStateCovariance"; - case 1718: return "delete_DiscreteExtendedKalmanFilterHelper"; - case 1719: return "output_dimensions_with_magnetometer_get"; - case 1720: return "output_dimensions_without_magnetometer_get"; - case 1721: return "input_dimensions_get"; - case 1722: return "AttitudeQuaternionEKFParameters_time_step_in_seconds_get"; - case 1723: return "AttitudeQuaternionEKFParameters_time_step_in_seconds_set"; - case 1724: return "AttitudeQuaternionEKFParameters_bias_correlation_time_factor_get"; - case 1725: return "AttitudeQuaternionEKFParameters_bias_correlation_time_factor_set"; - case 1726: return "AttitudeQuaternionEKFParameters_accelerometer_noise_variance_get"; - case 1727: return "AttitudeQuaternionEKFParameters_accelerometer_noise_variance_set"; - case 1728: return "AttitudeQuaternionEKFParameters_magnetometer_noise_variance_get"; - case 1729: return "AttitudeQuaternionEKFParameters_magnetometer_noise_variance_set"; - case 1730: return "AttitudeQuaternionEKFParameters_gyroscope_noise_variance_get"; - case 1731: return "AttitudeQuaternionEKFParameters_gyroscope_noise_variance_set"; - case 1732: return "AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_get"; - case 1733: return "AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_set"; - case 1734: return "AttitudeQuaternionEKFParameters_initial_orientation_error_variance_get"; - case 1735: return "AttitudeQuaternionEKFParameters_initial_orientation_error_variance_set"; - case 1736: return "AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_get"; - case 1737: return "AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_set"; - case 1738: return "AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_get"; - case 1739: return "AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_set"; - case 1740: return "AttitudeQuaternionEKFParameters_use_magnetometer_measurements_get"; - case 1741: return "AttitudeQuaternionEKFParameters_use_magnetometer_measurements_set"; - case 1742: return "new_AttitudeQuaternionEKFParameters"; - case 1743: return "delete_AttitudeQuaternionEKFParameters"; - case 1744: return "new_AttitudeQuaternionEKF"; - case 1745: return "AttitudeQuaternionEKF_getParameters"; - case 1746: return "AttitudeQuaternionEKF_setParameters"; - case 1747: return "AttitudeQuaternionEKF_setGravityDirection"; - case 1748: return "AttitudeQuaternionEKF_setTimeStepInSeconds"; - case 1749: return "AttitudeQuaternionEKF_setBiasCorrelationTimeFactor"; - case 1750: return "AttitudeQuaternionEKF_useMagnetometerMeasurements"; - case 1751: return "AttitudeQuaternionEKF_setMeasurementNoiseVariance"; - case 1752: return "AttitudeQuaternionEKF_setSystemNoiseVariance"; - case 1753: return "AttitudeQuaternionEKF_setInitialStateCovariance"; - case 1754: return "AttitudeQuaternionEKF_initializeFilter"; - case 1755: return "AttitudeQuaternionEKF_updateFilterWithMeasurements"; - case 1756: return "AttitudeQuaternionEKF_propagateStates"; - case 1757: return "AttitudeQuaternionEKF_getOrientationEstimateAsRotationMatrix"; - case 1758: return "AttitudeQuaternionEKF_getOrientationEstimateAsQuaternion"; - case 1759: return "AttitudeQuaternionEKF_getOrientationEstimateAsRPY"; - case 1760: return "AttitudeQuaternionEKF_getInternalStateSize"; - case 1761: return "AttitudeQuaternionEKF_getInternalState"; - case 1762: return "AttitudeQuaternionEKF_getDefaultInternalInitialState"; - case 1763: return "AttitudeQuaternionEKF_setInternalState"; - case 1764: return "AttitudeQuaternionEKF_setInternalStateInitialOrientation"; - case 1765: return "delete_AttitudeQuaternionEKF"; - case 1766: return "_wrap_estimateInertialParametersFromLinkBoundingBoxesAndTotalMass"; - case 1767: return "_wrap_computeBoundingBoxFromShape"; - case 1768: return "_wrap_computeBoxVertices"; - case 1769: return "new_KinDynComputations"; - case 1770: return "delete_KinDynComputations"; - case 1771: return "KinDynComputations_loadRobotModel"; - case 1772: return "KinDynComputations_isValid"; - case 1773: return "KinDynComputations_setFrameVelocityRepresentation"; - case 1774: return "KinDynComputations_getFrameVelocityRepresentation"; - case 1775: return "KinDynComputations_getNrOfDegreesOfFreedom"; - case 1776: return "KinDynComputations_getDescriptionOfDegreeOfFreedom"; - case 1777: return "KinDynComputations_getDescriptionOfDegreesOfFreedom"; - case 1778: return "KinDynComputations_getNrOfLinks"; - case 1779: return "KinDynComputations_getNrOfFrames"; - case 1780: return "KinDynComputations_getFloatingBase"; - case 1781: return "KinDynComputations_setFloatingBase"; - case 1782: return "KinDynComputations_model"; - case 1783: return "KinDynComputations_getRobotModel"; - case 1784: return "KinDynComputations_getRelativeJacobianSparsityPattern"; - case 1785: return "KinDynComputations_getFrameFreeFloatingJacobianSparsityPattern"; - case 1786: return "KinDynComputations_setJointPos"; - case 1787: return "KinDynComputations_setRobotState"; - case 1788: return "KinDynComputations_getRobotState"; - case 1789: return "KinDynComputations_getWorldBaseTransform"; - case 1790: return "KinDynComputations_getBaseTwist"; - case 1791: return "KinDynComputations_getJointPos"; - case 1792: return "KinDynComputations_getJointVel"; - case 1793: return "KinDynComputations_getModelVel"; - case 1794: return "KinDynComputations_getFrameIndex"; - case 1795: return "KinDynComputations_getFrameName"; - case 1796: return "KinDynComputations_getWorldTransform"; - case 1797: return "KinDynComputations_getWorldTransformsAsHomogeneous"; - case 1798: return "KinDynComputations_getRelativeTransformExplicit"; - case 1799: return "KinDynComputations_getRelativeTransform"; - case 1800: return "KinDynComputations_getFrameVel"; - case 1801: return "KinDynComputations_getFrameAcc"; - case 1802: return "KinDynComputations_getFrameFreeFloatingJacobian"; - case 1803: return "KinDynComputations_getRelativeJacobian"; - case 1804: return "KinDynComputations_getRelativeJacobianExplicit"; - case 1805: return "KinDynComputations_getFrameBiasAcc"; - case 1806: return "KinDynComputations_getCenterOfMassPosition"; - case 1807: return "KinDynComputations_getCenterOfMassVelocity"; - case 1808: return "KinDynComputations_getCenterOfMassJacobian"; - case 1809: return "KinDynComputations_getCenterOfMassBiasAcc"; - case 1810: return "KinDynComputations_getAverageVelocity"; - case 1811: return "KinDynComputations_getAverageVelocityJacobian"; - case 1812: return "KinDynComputations_getCentroidalAverageVelocity"; - case 1813: return "KinDynComputations_getCentroidalAverageVelocityJacobian"; - case 1814: return "KinDynComputations_getLinearAngularMomentum"; - case 1815: return "KinDynComputations_getLinearAngularMomentumJacobian"; - case 1816: return "KinDynComputations_getCentroidalTotalMomentum"; - case 1817: return "KinDynComputations_getCentroidalTotalMomentumJacobian"; - case 1818: return "KinDynComputations_getFreeFloatingMassMatrix"; - case 1819: return "KinDynComputations_inverseDynamics"; - case 1820: return "KinDynComputations_inverseDynamicsWithInternalJointForceTorques"; - case 1821: return "KinDynComputations_generalizedBiasForces"; - case 1822: return "KinDynComputations_generalizedGravityForces"; - case 1823: return "KinDynComputations_generalizedExternalForces"; - case 1824: return "KinDynComputations_inverseDynamicsInertialParametersRegressor"; - case 1825: return "Matrix4x4Vector_pop"; - case 1826: return "Matrix4x4Vector_brace"; - case 1827: return "Matrix4x4Vector_setbrace"; - case 1828: return "Matrix4x4Vector_append"; - case 1829: return "Matrix4x4Vector_empty"; - case 1830: return "Matrix4x4Vector_size"; - case 1831: return "Matrix4x4Vector_swap"; - case 1832: return "Matrix4x4Vector_begin"; - case 1833: return "Matrix4x4Vector_end"; - case 1834: return "Matrix4x4Vector_rbegin"; - case 1835: return "Matrix4x4Vector_rend"; - case 1836: return "Matrix4x4Vector_clear"; - case 1837: return "Matrix4x4Vector_get_allocator"; - case 1838: return "Matrix4x4Vector_pop_back"; - case 1839: return "Matrix4x4Vector_erase"; - case 1840: return "new_Matrix4x4Vector"; - case 1841: return "Matrix4x4Vector_push_back"; - case 1842: return "Matrix4x4Vector_front"; - case 1843: return "Matrix4x4Vector_back"; - case 1844: return "Matrix4x4Vector_assign"; - case 1845: return "Matrix4x4Vector_resize"; - case 1846: return "Matrix4x4Vector_insert"; - case 1847: return "Matrix4x4Vector_reserve"; - case 1848: return "Matrix4x4Vector_capacity"; - case 1849: return "Matrix4x4Vector_toMatlab"; - case 1850: return "delete_Matrix4x4Vector"; - case 1851: return "ICameraAnimator_enableMouseControl"; - case 1852: return "ICameraAnimator_getMoveSpeed"; - case 1853: return "ICameraAnimator_setMoveSpeed"; - case 1854: return "ICameraAnimator_getRotateSpeed"; - case 1855: return "ICameraAnimator_setRotateSpeed"; - case 1856: return "ICameraAnimator_getZoomSpeed"; - case 1857: return "ICameraAnimator_setZoomSpeed"; - case 1858: return "delete_ICameraAnimator"; - case 1859: return "delete_ICamera"; - case 1860: return "ICamera_setPosition"; - case 1861: return "ICamera_setTarget"; - case 1862: return "ICamera_getPosition"; - case 1863: return "ICamera_getTarget"; - case 1864: return "ICamera_setUpVector"; - case 1865: return "ICamera_animator"; - case 1866: return "ColorViz_r_get"; - case 1867: return "ColorViz_r_set"; - case 1868: return "ColorViz_g_get"; - case 1869: return "ColorViz_g_set"; - case 1870: return "ColorViz_b_get"; - case 1871: return "ColorViz_b_set"; - case 1872: return "ColorViz_a_get"; - case 1873: return "ColorViz_a_set"; - case 1874: return "new_ColorViz"; - case 1875: return "delete_ColorViz"; - case 1876: return "PixelViz_width_get"; - case 1877: return "PixelViz_width_set"; - case 1878: return "PixelViz_height_get"; - case 1879: return "PixelViz_height_set"; - case 1880: return "new_PixelViz"; - case 1881: return "delete_PixelViz"; - case 1882: return "delete_ILight"; - case 1883: return "ILight_getName"; - case 1884: return "ILight_setType"; - case 1885: return "ILight_getType"; - case 1886: return "ILight_setPosition"; - case 1887: return "ILight_getPosition"; - case 1888: return "ILight_setDirection"; - case 1889: return "ILight_getDirection"; - case 1890: return "ILight_setAmbientColor"; - case 1891: return "ILight_getAmbientColor"; - case 1892: return "ILight_setSpecularColor"; - case 1893: return "ILight_getSpecularColor"; - case 1894: return "ILight_setDiffuseColor"; - case 1895: return "ILight_getDiffuseColor"; - case 1896: return "delete_IEnvironment"; - case 1897: return "IEnvironment_getElements"; - case 1898: return "IEnvironment_setElementVisibility"; - case 1899: return "IEnvironment_setBackgroundColor"; - case 1900: return "IEnvironment_setFloorGridColor"; - case 1901: return "IEnvironment_setAmbientLight"; - case 1902: return "IEnvironment_getLights"; - case 1903: return "IEnvironment_addLight"; - case 1904: return "IEnvironment_lightViz"; - case 1905: return "IEnvironment_removeLight"; - case 1906: return "delete_IJetsVisualization"; - case 1907: return "IJetsVisualization_setJetsFrames"; - case 1908: return "IJetsVisualization_getNrOfJets"; - case 1909: return "IJetsVisualization_getJetDirection"; - case 1910: return "IJetsVisualization_setJetDirection"; - case 1911: return "IJetsVisualization_setJetColor"; - case 1912: return "IJetsVisualization_setJetsDimensions"; - case 1913: return "IJetsVisualization_setJetsIntensity"; - case 1914: return "delete_ILabel"; - case 1915: return "ILabel_setText"; - case 1916: return "ILabel_getText"; - case 1917: return "ILabel_setSize"; - case 1918: return "ILabel_width"; - case 1919: return "ILabel_height"; - case 1920: return "ILabel_setPosition"; - case 1921: return "ILabel_getPosition"; - case 1922: return "ILabel_setColor"; - case 1923: return "ILabel_setVisible"; - case 1924: return "delete_IVectorsVisualization"; - case 1925: return "IVectorsVisualization_addVector"; - case 1926: return "IVectorsVisualization_getNrOfVectors"; - case 1927: return "IVectorsVisualization_getVector"; - case 1928: return "IVectorsVisualization_updateVector"; - case 1929: return "IVectorsVisualization_setVectorColor"; - case 1930: return "IVectorsVisualization_setVectorsDefaultColor"; - case 1931: return "IVectorsVisualization_setVectorsColor"; - case 1932: return "IVectorsVisualization_setVectorsAspect"; - case 1933: return "IVectorsVisualization_setVisible"; - case 1934: return "IVectorsVisualization_getVectorLabel"; - case 1935: return "delete_IFrameVisualization"; - case 1936: return "IFrameVisualization_addFrame"; - case 1937: return "IFrameVisualization_setVisible"; - case 1938: return "IFrameVisualization_getNrOfFrames"; - case 1939: return "IFrameVisualization_getFrameTransform"; - case 1940: return "IFrameVisualization_updateFrame"; - case 1941: return "IFrameVisualization_getFrameLabel"; - case 1942: return "delete_IModelVisualization"; - case 1943: return "IModelVisualization_setPositions"; - case 1944: return "IModelVisualization_setLinkPositions"; - case 1945: return "IModelVisualization_model"; - case 1946: return "IModelVisualization_getInstanceName"; - case 1947: return "IModelVisualization_setModelVisibility"; - case 1948: return "IModelVisualization_setModelColor"; - case 1949: return "IModelVisualization_resetModelColor"; - case 1950: return "IModelVisualization_setLinkColor"; - case 1951: return "IModelVisualization_resetLinkColor"; - case 1952: return "IModelVisualization_getLinkNames"; - case 1953: return "IModelVisualization_setLinkVisibility"; - case 1954: return "IModelVisualization_getFeatures"; - case 1955: return "IModelVisualization_setFeatureVisibility"; - case 1956: return "IModelVisualization_jets"; - case 1957: return "IModelVisualization_getWorldLinkTransform"; - case 1958: return "IModelVisualization_getWorldFrameTransform"; - case 1959: return "IModelVisualization_label"; - case 1960: return "delete_ITexture"; - case 1961: return "ITexture_environment"; - case 1962: return "ITexture_getPixelColor"; - case 1963: return "ITexture_getPixels"; - case 1964: return "ITexture_drawToFile"; - case 1965: return "ITexture_enableDraw"; - case 1966: return "ITexture_width"; - case 1967: return "ITexture_height"; - case 1968: return "ITexture_setSubDrawArea"; - case 1969: return "VisualizerOptions_verbose_get"; - case 1970: return "VisualizerOptions_verbose_set"; - case 1971: return "VisualizerOptions_winWidth_get"; - case 1972: return "VisualizerOptions_winWidth_set"; - case 1973: return "VisualizerOptions_winHeight_get"; - case 1974: return "VisualizerOptions_winHeight_set"; - case 1975: return "VisualizerOptions_rootFrameArrowsDimension_get"; - case 1976: return "VisualizerOptions_rootFrameArrowsDimension_set"; - case 1977: return "new_VisualizerOptions"; - case 1978: return "delete_VisualizerOptions"; - case 1979: return "delete_ITexturesHandler"; - case 1980: return "ITexturesHandler_add"; - case 1981: return "ITexturesHandler_get"; - case 1982: return "new_Visualizer"; - case 1983: return "delete_Visualizer"; - case 1984: return "Visualizer_init"; - case 1985: return "Visualizer_getNrOfVisualizedModels"; - case 1986: return "Visualizer_getModelInstanceName"; - case 1987: return "Visualizer_getModelInstanceIndex"; - case 1988: return "Visualizer_addModel"; - case 1989: return "Visualizer_modelViz"; - case 1990: return "Visualizer_camera"; - case 1991: return "Visualizer_enviroment"; - case 1992: return "Visualizer_environment"; - case 1993: return "Visualizer_vectors"; - case 1994: return "Visualizer_frames"; - case 1995: return "Visualizer_textures"; - case 1996: return "Visualizer_getLabel"; - case 1997: return "Visualizer_width"; - case 1998: return "Visualizer_height"; - case 1999: return "Visualizer_run"; - case 2000: return "Visualizer_draw"; - case 2001: return "Visualizer_subDraw"; - case 2002: return "Visualizer_drawToFile"; - case 2003: return "Visualizer_close"; - case 2004: return "Visualizer_isWindowActive"; - case 2005: return "Visualizer_setColorPalette"; - case 2006: return "Polygon_m_vertices_get"; - case 2007: return "Polygon_m_vertices_set"; - case 2008: return "new_Polygon"; - case 2009: return "Polygon_setNrOfVertices"; - case 2010: return "Polygon_getNrOfVertices"; - case 2011: return "Polygon_isValid"; - case 2012: return "Polygon_applyTransform"; - case 2013: return "Polygon_paren"; - case 2014: return "Polygon_XYRectangleFromOffsets"; - case 2015: return "delete_Polygon"; - case 2016: return "Polygon2D_m_vertices_get"; - case 2017: return "Polygon2D_m_vertices_set"; - case 2018: return "new_Polygon2D"; - case 2019: return "Polygon2D_setNrOfVertices"; - case 2020: return "Polygon2D_getNrOfVertices"; - case 2021: return "Polygon2D_isValid"; - case 2022: return "Polygon2D_paren"; - case 2023: return "delete_Polygon2D"; - case 2024: return "ConvexHullProjectionConstraint_setActive"; - case 2025: return "ConvexHullProjectionConstraint_isActive"; - case 2026: return "ConvexHullProjectionConstraint_getNrOfConstraints"; - case 2027: return "ConvexHullProjectionConstraint_projectedConvexHull_get"; - case 2028: return "ConvexHullProjectionConstraint_projectedConvexHull_set"; - case 2029: return "ConvexHullProjectionConstraint_A_get"; - case 2030: return "ConvexHullProjectionConstraint_A_set"; - case 2031: return "ConvexHullProjectionConstraint_b_get"; - case 2032: return "ConvexHullProjectionConstraint_b_set"; - case 2033: return "ConvexHullProjectionConstraint_P_get"; - case 2034: return "ConvexHullProjectionConstraint_P_set"; - case 2035: return "ConvexHullProjectionConstraint_Pdirection_get"; - case 2036: return "ConvexHullProjectionConstraint_Pdirection_set"; - case 2037: return "ConvexHullProjectionConstraint_AtimesP_get"; - case 2038: return "ConvexHullProjectionConstraint_AtimesP_set"; - case 2039: return "ConvexHullProjectionConstraint_o_get"; - case 2040: return "ConvexHullProjectionConstraint_o_set"; - case 2041: return "ConvexHullProjectionConstraint_buildConvexHull"; - case 2042: return "ConvexHullProjectionConstraint_supportFrameIndices_get"; - case 2043: return "ConvexHullProjectionConstraint_supportFrameIndices_set"; - case 2044: return "ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_get"; - case 2045: return "ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_set"; - case 2046: return "ConvexHullProjectionConstraint_project"; - case 2047: return "ConvexHullProjectionConstraint_computeMargin"; - case 2048: return "ConvexHullProjectionConstraint_setProjectionAlongDirection"; - case 2049: return "ConvexHullProjectionConstraint_projectAlongDirection"; - case 2050: return "new_ConvexHullProjectionConstraint"; - case 2051: return "delete_ConvexHullProjectionConstraint"; - case 2052: return "_wrap_sizeOfRotationParametrization"; - case 2053: return "new_InverseKinematics"; - case 2054: return "delete_InverseKinematics"; - case 2055: return "InverseKinematics_loadModelFromFile"; - case 2056: return "InverseKinematics_setModel"; - case 2057: return "InverseKinematics_setJointLimits"; - case 2058: return "InverseKinematics_getJointLimits"; - case 2059: return "InverseKinematics_clearProblem"; - case 2060: return "InverseKinematics_setFloatingBaseOnFrameNamed"; - case 2061: return "InverseKinematics_setCurrentRobotConfiguration"; - case 2062: return "InverseKinematics_setJointConfiguration"; - case 2063: return "InverseKinematics_setRotationParametrization"; - case 2064: return "InverseKinematics_rotationParametrization"; - case 2065: return "InverseKinematics_setMaxIterations"; - case 2066: return "InverseKinematics_maxIterations"; - case 2067: return "InverseKinematics_setMaxCPUTime"; - case 2068: return "InverseKinematics_maxCPUTime"; - case 2069: return "InverseKinematics_setCostTolerance"; - case 2070: return "InverseKinematics_costTolerance"; - case 2071: return "InverseKinematics_setConstraintsTolerance"; - case 2072: return "InverseKinematics_constraintsTolerance"; - case 2073: return "InverseKinematics_setVerbosity"; - case 2074: return "InverseKinematics_linearSolverName"; - case 2075: return "InverseKinematics_setLinearSolverName"; - case 2076: return "InverseKinematics_addFrameConstraint"; - case 2077: return "InverseKinematics_addFramePositionConstraint"; - case 2078: return "InverseKinematics_addFrameRotationConstraint"; - case 2079: return "InverseKinematics_activateFrameConstraint"; - case 2080: return "InverseKinematics_deactivateFrameConstraint"; - case 2081: return "InverseKinematics_isFrameConstraintActive"; - case 2082: return "InverseKinematics_addCenterOfMassProjectionConstraint"; - case 2083: return "InverseKinematics_getCenterOfMassProjectionMargin"; - case 2084: return "InverseKinematics_getCenterOfMassProjectConstraintConvexHull"; - case 2085: return "InverseKinematics_addTarget"; - case 2086: return "InverseKinematics_addPositionTarget"; - case 2087: return "InverseKinematics_addRotationTarget"; - case 2088: return "InverseKinematics_updateTarget"; - case 2089: return "InverseKinematics_updatePositionTarget"; - case 2090: return "InverseKinematics_updateRotationTarget"; - case 2091: return "InverseKinematics_setDefaultTargetResolutionMode"; - case 2092: return "InverseKinematics_defaultTargetResolutionMode"; - case 2093: return "InverseKinematics_setTargetResolutionMode"; - case 2094: return "InverseKinematics_targetResolutionMode"; - case 2095: return "InverseKinematics_setDesiredFullJointsConfiguration"; - case 2096: return "InverseKinematics_setDesiredReducedJointConfiguration"; - case 2097: return "InverseKinematics_setFullJointsInitialCondition"; - case 2098: return "InverseKinematics_setReducedInitialCondition"; - case 2099: return "InverseKinematics_solve"; - case 2100: return "InverseKinematics_getFullJointsSolution"; - case 2101: return "InverseKinematics_getReducedSolution"; - case 2102: return "InverseKinematics_getPoseForFrame"; - case 2103: return "InverseKinematics_fullModel"; - case 2104: return "InverseKinematics_reducedModel"; - case 2105: return "InverseKinematics_setCOMTarget"; - case 2106: return "InverseKinematics_setCOMAsConstraint"; - case 2107: return "InverseKinematics_setCOMAsConstraintTolerance"; - case 2108: return "InverseKinematics_isCOMAConstraint"; - case 2109: return "InverseKinematics_isCOMTargetActive"; - case 2110: return "InverseKinematics_deactivateCOMTarget"; - case 2111: return "InverseKinematics_setCOMConstraintProjectionDirection"; + case 71: return "MatrixDynSizeVector_pop"; + case 72: return "MatrixDynSizeVector_brace"; + case 73: return "MatrixDynSizeVector_setbrace"; + case 74: return "MatrixDynSizeVector_append"; + case 75: return "MatrixDynSizeVector_empty"; + case 76: return "MatrixDynSizeVector_size"; + case 77: return "MatrixDynSizeVector_swap"; + case 78: return "MatrixDynSizeVector_begin"; + case 79: return "MatrixDynSizeVector_end"; + case 80: return "MatrixDynSizeVector_rbegin"; + case 81: return "MatrixDynSizeVector_rend"; + case 82: return "MatrixDynSizeVector_clear"; + case 83: return "MatrixDynSizeVector_get_allocator"; + case 84: return "MatrixDynSizeVector_pop_back"; + case 85: return "MatrixDynSizeVector_erase"; + case 86: return "new_MatrixDynSizeVector"; + case 87: return "MatrixDynSizeVector_push_back"; + case 88: return "MatrixDynSizeVector_front"; + case 89: return "MatrixDynSizeVector_back"; + case 90: return "MatrixDynSizeVector_assign"; + case 91: return "MatrixDynSizeVector_resize"; + case 92: return "MatrixDynSizeVector_insert"; + case 93: return "MatrixDynSizeVector_reserve"; + case 94: return "MatrixDynSizeVector_capacity"; + case 95: return "delete_MatrixDynSizeVector"; + case 96: return "VectorDynSizeVector_pop"; + case 97: return "VectorDynSizeVector_brace"; + case 98: return "VectorDynSizeVector_setbrace"; + case 99: return "VectorDynSizeVector_append"; + case 100: return "VectorDynSizeVector_empty"; + case 101: return "VectorDynSizeVector_size"; + case 102: return "VectorDynSizeVector_swap"; + case 103: return "VectorDynSizeVector_begin"; + case 104: return "VectorDynSizeVector_end"; + case 105: return "VectorDynSizeVector_rbegin"; + case 106: return "VectorDynSizeVector_rend"; + case 107: return "VectorDynSizeVector_clear"; + case 108: return "VectorDynSizeVector_get_allocator"; + case 109: return "VectorDynSizeVector_pop_back"; + case 110: return "VectorDynSizeVector_erase"; + case 111: return "new_VectorDynSizeVector"; + case 112: return "VectorDynSizeVector_push_back"; + case 113: return "VectorDynSizeVector_front"; + case 114: return "VectorDynSizeVector_back"; + case 115: return "VectorDynSizeVector_assign"; + case 116: return "VectorDynSizeVector_resize"; + case 117: return "VectorDynSizeVector_insert"; + case 118: return "VectorDynSizeVector_reserve"; + case 119: return "VectorDynSizeVector_capacity"; + case 120: return "delete_VectorDynSizeVector"; + case 121: return "IndexVector_pop"; + case 122: return "IndexVector_brace"; + case 123: return "IndexVector_setbrace"; + case 124: return "IndexVector_append"; + case 125: return "IndexVector_empty"; + case 126: return "IndexVector_size"; + case 127: return "IndexVector_swap"; + case 128: return "IndexVector_begin"; + case 129: return "IndexVector_end"; + case 130: return "IndexVector_rbegin"; + case 131: return "IndexVector_rend"; + case 132: return "IndexVector_clear"; + case 133: return "IndexVector_get_allocator"; + case 134: return "IndexVector_pop_back"; + case 135: return "IndexVector_erase"; + case 136: return "new_IndexVector"; + case 137: return "IndexVector_push_back"; + case 138: return "IndexVector_front"; + case 139: return "IndexVector_back"; + case 140: return "IndexVector_assign"; + case 141: return "IndexVector_resize"; + case 142: return "IndexVector_insert"; + case 143: return "IndexVector_reserve"; + case 144: return "IndexVector_capacity"; + case 145: return "delete_IndexVector"; + case 146: return "BerdySensors_pop"; + case 147: return "BerdySensors_brace"; + case 148: return "BerdySensors_setbrace"; + case 149: return "BerdySensors_append"; + case 150: return "BerdySensors_empty"; + case 151: return "BerdySensors_size"; + case 152: return "BerdySensors_swap"; + case 153: return "BerdySensors_begin"; + case 154: return "BerdySensors_end"; + case 155: return "BerdySensors_rbegin"; + case 156: return "BerdySensors_rend"; + case 157: return "BerdySensors_clear"; + case 158: return "BerdySensors_get_allocator"; + case 159: return "BerdySensors_pop_back"; + case 160: return "BerdySensors_erase"; + case 161: return "new_BerdySensors"; + case 162: return "BerdySensors_push_back"; + case 163: return "BerdySensors_front"; + case 164: return "BerdySensors_back"; + case 165: return "BerdySensors_assign"; + case 166: return "BerdySensors_resize"; + case 167: return "BerdySensors_insert"; + case 168: return "BerdySensors_reserve"; + case 169: return "BerdySensors_capacity"; + case 170: return "delete_BerdySensors"; + case 171: return "BerdyDynamicVariables_pop"; + case 172: return "BerdyDynamicVariables_brace"; + case 173: return "BerdyDynamicVariables_setbrace"; + case 174: return "BerdyDynamicVariables_append"; + case 175: return "BerdyDynamicVariables_empty"; + case 176: return "BerdyDynamicVariables_size"; + case 177: return "BerdyDynamicVariables_swap"; + case 178: return "BerdyDynamicVariables_begin"; + case 179: return "BerdyDynamicVariables_end"; + case 180: return "BerdyDynamicVariables_rbegin"; + case 181: return "BerdyDynamicVariables_rend"; + case 182: return "BerdyDynamicVariables_clear"; + case 183: return "BerdyDynamicVariables_get_allocator"; + case 184: return "BerdyDynamicVariables_pop_back"; + case 185: return "BerdyDynamicVariables_erase"; + case 186: return "new_BerdyDynamicVariables"; + case 187: return "BerdyDynamicVariables_push_back"; + case 188: return "BerdyDynamicVariables_front"; + case 189: return "BerdyDynamicVariables_back"; + case 190: return "BerdyDynamicVariables_assign"; + case 191: return "BerdyDynamicVariables_resize"; + case 192: return "BerdyDynamicVariables_insert"; + case 193: return "BerdyDynamicVariables_reserve"; + case 194: return "BerdyDynamicVariables_capacity"; + case 195: return "delete_BerdyDynamicVariables"; + case 196: return "_wrap_reportInfo"; + case 197: return "_wrap_reportDebug"; + case 198: return "IndexRange_offset_get"; + case 199: return "IndexRange_offset_set"; + case 200: return "IndexRange_size_get"; + case 201: return "IndexRange_size_set"; + case 202: return "IndexRange_isValid"; + case 203: return "IndexRange_InvalidRange"; + case 204: return "new_IndexRange"; + case 205: return "delete_IndexRange"; + case 206: return "_wrap_checkDoublesAreEqual"; + case 207: return "new_MatrixDynSize"; + case 208: return "delete_MatrixDynSize"; + case 209: return "MatrixDynSize_paren"; + case 210: return "MatrixDynSize_getVal"; + case 211: return "MatrixDynSize_setVal"; + case 212: return "MatrixDynSize_rows"; + case 213: return "MatrixDynSize_cols"; + case 214: return "MatrixDynSize_data"; + case 215: return "MatrixDynSize_zero"; + case 216: return "MatrixDynSize_resize"; + case 217: return "MatrixDynSize_reserve"; + case 218: return "MatrixDynSize_capacity"; + case 219: return "MatrixDynSize_shrink_to_fit"; + case 220: return "MatrixDynSize_fillRowMajorBuffer"; + case 221: return "MatrixDynSize_fillColMajorBuffer"; + case 222: return "MatrixDynSize_toString"; + case 223: return "MatrixDynSize_display"; + case 224: return "MatrixDynSize_toMatlab"; + case 225: return "MatrixDynSize_fromMatlab"; + case 226: return "new_SparseMatrixRowMajor"; + case 227: return "delete_SparseMatrixRowMajor"; + case 228: return "SparseMatrixRowMajor_numberOfNonZeros"; + case 229: return "SparseMatrixRowMajor_resize"; + case 230: return "SparseMatrixRowMajor_reserve"; + case 231: return "SparseMatrixRowMajor_zero"; + case 232: return "SparseMatrixRowMajor_setFromConstTriplets"; + case 233: return "SparseMatrixRowMajor_setFromTriplets"; + case 234: return "SparseMatrixRowMajor_sparseMatrixFromTriplets"; + case 235: return "SparseMatrixRowMajor_paren"; + case 236: return "SparseMatrixRowMajor_getValue"; + case 237: return "SparseMatrixRowMajor_setValue"; + case 238: return "SparseMatrixRowMajor_rows"; + case 239: return "SparseMatrixRowMajor_columns"; + case 240: return "SparseMatrixRowMajor_description"; + case 241: return "SparseMatrixRowMajor_toMatlab"; + case 242: return "SparseMatrixRowMajor_toMatlabDense"; + case 243: return "SparseMatrixRowMajor_fromMatlab"; + case 244: return "new_SparseMatrixColMajor"; + case 245: return "delete_SparseMatrixColMajor"; + case 246: return "SparseMatrixColMajor_numberOfNonZeros"; + case 247: return "SparseMatrixColMajor_resize"; + case 248: return "SparseMatrixColMajor_reserve"; + case 249: return "SparseMatrixColMajor_zero"; + case 250: return "SparseMatrixColMajor_setFromConstTriplets"; + case 251: return "SparseMatrixColMajor_setFromTriplets"; + case 252: return "SparseMatrixColMajor_sparseMatrixFromTriplets"; + case 253: return "SparseMatrixColMajor_paren"; + case 254: return "SparseMatrixColMajor_getValue"; + case 255: return "SparseMatrixColMajor_setValue"; + case 256: return "SparseMatrixColMajor_rows"; + case 257: return "SparseMatrixColMajor_columns"; + case 258: return "SparseMatrixColMajor_description"; + case 259: return "SparseMatrixColMajor_toMatlab"; + case 260: return "SparseMatrixColMajor_toMatlabDense"; + case 261: return "SparseMatrixColMajor_fromMatlab"; + case 262: return "new_VectorDynSize"; + case 263: return "delete_VectorDynSize"; + case 264: return "VectorDynSize_paren"; + case 265: return "VectorDynSize_brace"; + case 266: return "VectorDynSize_getVal"; + case 267: return "VectorDynSize_setVal"; + case 268: return "VectorDynSize_cbegin"; + case 269: return "VectorDynSize_cend"; + case 270: return "VectorDynSize_begin"; + case 271: return "VectorDynSize_end"; + case 272: return "VectorDynSize_size"; + case 273: return "VectorDynSize_data"; + case 274: return "VectorDynSize_zero"; + case 275: return "VectorDynSize_reserve"; + case 276: return "VectorDynSize_resize"; + case 277: return "VectorDynSize_shrink_to_fit"; + case 278: return "VectorDynSize_capacity"; + case 279: return "VectorDynSize_fillBuffer"; + case 280: return "VectorDynSize_toString"; + case 281: return "VectorDynSize_display"; + case 282: return "VectorDynSize_toMatlab"; + case 283: return "VectorDynSize_fromMatlab"; + case 284: return "new_Matrix1x6"; + case 285: return "Matrix1x6_paren"; + case 286: return "Matrix1x6_getVal"; + case 287: return "Matrix1x6_setVal"; + case 288: return "Matrix1x6_rows"; + case 289: return "Matrix1x6_cols"; + case 290: return "Matrix1x6_data"; + case 291: return "Matrix1x6_zero"; + case 292: return "Matrix1x6_fillRowMajorBuffer"; + case 293: return "Matrix1x6_fillColMajorBuffer"; + case 294: return "Matrix1x6_toString"; + case 295: return "Matrix1x6_display"; + case 296: return "Matrix1x6_toMatlab"; + case 297: return "Matrix1x6_fromMatlab"; + case 298: return "delete_Matrix1x6"; + case 299: return "new_Matrix2x3"; + case 300: return "Matrix2x3_paren"; + case 301: return "Matrix2x3_getVal"; + case 302: return "Matrix2x3_setVal"; + case 303: return "Matrix2x3_rows"; + case 304: return "Matrix2x3_cols"; + case 305: return "Matrix2x3_data"; + case 306: return "Matrix2x3_zero"; + case 307: return "Matrix2x3_fillRowMajorBuffer"; + case 308: return "Matrix2x3_fillColMajorBuffer"; + case 309: return "Matrix2x3_toString"; + case 310: return "Matrix2x3_display"; + case 311: return "Matrix2x3_toMatlab"; + case 312: return "Matrix2x3_fromMatlab"; + case 313: return "delete_Matrix2x3"; + case 314: return "new_Matrix3x3"; + case 315: return "Matrix3x3_paren"; + case 316: return "Matrix3x3_getVal"; + case 317: return "Matrix3x3_setVal"; + case 318: return "Matrix3x3_rows"; + case 319: return "Matrix3x3_cols"; + case 320: return "Matrix3x3_data"; + case 321: return "Matrix3x3_zero"; + case 322: return "Matrix3x3_fillRowMajorBuffer"; + case 323: return "Matrix3x3_fillColMajorBuffer"; + case 324: return "Matrix3x3_toString"; + case 325: return "Matrix3x3_display"; + case 326: return "Matrix3x3_toMatlab"; + case 327: return "Matrix3x3_fromMatlab"; + case 328: return "delete_Matrix3x3"; + case 329: return "new_Matrix4x4"; + case 330: return "Matrix4x4_paren"; + case 331: return "Matrix4x4_getVal"; + case 332: return "Matrix4x4_setVal"; + case 333: return "Matrix4x4_rows"; + case 334: return "Matrix4x4_cols"; + case 335: return "Matrix4x4_data"; + case 336: return "Matrix4x4_zero"; + case 337: return "Matrix4x4_fillRowMajorBuffer"; + case 338: return "Matrix4x4_fillColMajorBuffer"; + case 339: return "Matrix4x4_toString"; + case 340: return "Matrix4x4_display"; + case 341: return "Matrix4x4_toMatlab"; + case 342: return "Matrix4x4_fromMatlab"; + case 343: return "delete_Matrix4x4"; + case 344: return "new_Matrix6x6"; + case 345: return "Matrix6x6_paren"; + case 346: return "Matrix6x6_getVal"; + case 347: return "Matrix6x6_setVal"; + case 348: return "Matrix6x6_rows"; + case 349: return "Matrix6x6_cols"; + case 350: return "Matrix6x6_data"; + case 351: return "Matrix6x6_zero"; + case 352: return "Matrix6x6_fillRowMajorBuffer"; + case 353: return "Matrix6x6_fillColMajorBuffer"; + case 354: return "Matrix6x6_toString"; + case 355: return "Matrix6x6_display"; + case 356: return "Matrix6x6_toMatlab"; + case 357: return "Matrix6x6_fromMatlab"; + case 358: return "delete_Matrix6x6"; + case 359: return "new_Matrix6x10"; + case 360: return "Matrix6x10_paren"; + case 361: return "Matrix6x10_getVal"; + case 362: return "Matrix6x10_setVal"; + case 363: return "Matrix6x10_rows"; + case 364: return "Matrix6x10_cols"; + case 365: return "Matrix6x10_data"; + case 366: return "Matrix6x10_zero"; + case 367: return "Matrix6x10_fillRowMajorBuffer"; + case 368: return "Matrix6x10_fillColMajorBuffer"; + case 369: return "Matrix6x10_toString"; + case 370: return "Matrix6x10_display"; + case 371: return "Matrix6x10_toMatlab"; + case 372: return "Matrix6x10_fromMatlab"; + case 373: return "delete_Matrix6x10"; + case 374: return "new_Matrix10x16"; + case 375: return "Matrix10x16_paren"; + case 376: return "Matrix10x16_getVal"; + case 377: return "Matrix10x16_setVal"; + case 378: return "Matrix10x16_rows"; + case 379: return "Matrix10x16_cols"; + case 380: return "Matrix10x16_data"; + case 381: return "Matrix10x16_zero"; + case 382: return "Matrix10x16_fillRowMajorBuffer"; + case 383: return "Matrix10x16_fillColMajorBuffer"; + case 384: return "Matrix10x16_toString"; + case 385: return "Matrix10x16_display"; + case 386: return "Matrix10x16_toMatlab"; + case 387: return "Matrix10x16_fromMatlab"; + case 388: return "delete_Matrix10x16"; + case 389: return "new_Vector3"; + case 390: return "Vector3_paren"; + case 391: return "Vector3_brace"; + case 392: return "Vector3_getVal"; + case 393: return "Vector3_setVal"; + case 394: return "Vector3_cbegin"; + case 395: return "Vector3_cend"; + case 396: return "Vector3_begin"; + case 397: return "Vector3_end"; + case 398: return "Vector3_size"; + case 399: return "Vector3_data"; + case 400: return "Vector3_zero"; + case 401: return "Vector3_fillBuffer"; + case 402: return "Vector3_toString"; + case 403: return "Vector3_display"; + case 404: return "Vector3_toMatlab"; + case 405: return "Vector3_fromMatlab"; + case 406: return "delete_Vector3"; + case 407: return "new_Vector4"; + case 408: return "Vector4_paren"; + case 409: return "Vector4_brace"; + case 410: return "Vector4_getVal"; + case 411: return "Vector4_setVal"; + case 412: return "Vector4_cbegin"; + case 413: return "Vector4_cend"; + case 414: return "Vector4_begin"; + case 415: return "Vector4_end"; + case 416: return "Vector4_size"; + case 417: return "Vector4_data"; + case 418: return "Vector4_zero"; + case 419: return "Vector4_fillBuffer"; + case 420: return "Vector4_toString"; + case 421: return "Vector4_display"; + case 422: return "Vector4_toMatlab"; + case 423: return "Vector4_fromMatlab"; + case 424: return "delete_Vector4"; + case 425: return "new_Vector6"; + case 426: return "Vector6_paren"; + case 427: return "Vector6_brace"; + case 428: return "Vector6_getVal"; + case 429: return "Vector6_setVal"; + case 430: return "Vector6_cbegin"; + case 431: return "Vector6_cend"; + case 432: return "Vector6_begin"; + case 433: return "Vector6_end"; + case 434: return "Vector6_size"; + case 435: return "Vector6_data"; + case 436: return "Vector6_zero"; + case 437: return "Vector6_fillBuffer"; + case 438: return "Vector6_toString"; + case 439: return "Vector6_display"; + case 440: return "Vector6_toMatlab"; + case 441: return "Vector6_fromMatlab"; + case 442: return "delete_Vector6"; + case 443: return "new_Vector10"; + case 444: return "Vector10_paren"; + case 445: return "Vector10_brace"; + case 446: return "Vector10_getVal"; + case 447: return "Vector10_setVal"; + case 448: return "Vector10_cbegin"; + case 449: return "Vector10_cend"; + case 450: return "Vector10_begin"; + case 451: return "Vector10_end"; + case 452: return "Vector10_size"; + case 453: return "Vector10_data"; + case 454: return "Vector10_zero"; + case 455: return "Vector10_fillBuffer"; + case 456: return "Vector10_toString"; + case 457: return "Vector10_display"; + case 458: return "Vector10_toMatlab"; + case 459: return "Vector10_fromMatlab"; + case 460: return "delete_Vector10"; + case 461: return "new_Vector16"; + case 462: return "Vector16_paren"; + case 463: return "Vector16_brace"; + case 464: return "Vector16_getVal"; + case 465: return "Vector16_setVal"; + case 466: return "Vector16_cbegin"; + case 467: return "Vector16_cend"; + case 468: return "Vector16_begin"; + case 469: return "Vector16_end"; + case 470: return "Vector16_size"; + case 471: return "Vector16_data"; + case 472: return "Vector16_zero"; + case 473: return "Vector16_fillBuffer"; + case 474: return "Vector16_toString"; + case 475: return "Vector16_display"; + case 476: return "Vector16_toMatlab"; + case 477: return "Vector16_fromMatlab"; + case 478: return "delete_Vector16"; + case 479: return "new_Position"; + case 480: return "Position_changePoint"; + case 481: return "Position_changeRefPoint"; + case 482: return "Position_changeCoordinateFrame"; + case 483: return "Position_compose"; + case 484: return "Position_inverse"; + case 485: return "Position_changePointOf"; + case 486: return "Position_plus"; + case 487: return "Position_minus"; + case 488: return "Position_uminus"; + case 489: return "Position_mtimes"; + case 490: return "Position_toString"; + case 491: return "Position_display"; + case 492: return "Position_Zero"; + case 493: return "delete_Position"; + case 494: return "new_GeomVector3"; + case 495: return "GeomVector3_changeCoordFrame"; + case 496: return "GeomVector3_compose"; + case 497: return "GeomVector3_inverse"; + case 498: return "GeomVector3_dot"; + case 499: return "GeomVector3_plus"; + case 500: return "GeomVector3_minus"; + case 501: return "GeomVector3_uminus"; + case 502: return "GeomVector3_exp"; + case 503: return "GeomVector3_cross"; + case 504: return "delete_GeomVector3"; + case 505: return "new_SpatialMotionVectorBase"; + case 506: return "SpatialMotionVectorBase_getLinearVec3"; + case 507: return "SpatialMotionVectorBase_getAngularVec3"; + case 508: return "SpatialMotionVectorBase_setLinearVec3"; + case 509: return "SpatialMotionVectorBase_setAngularVec3"; + case 510: return "SpatialMotionVectorBase_paren"; + case 511: return "SpatialMotionVectorBase_getVal"; + case 512: return "SpatialMotionVectorBase_setVal"; + case 513: return "SpatialMotionVectorBase_size"; + case 514: return "SpatialMotionVectorBase_zero"; + case 515: return "SpatialMotionVectorBase_changePoint"; + case 516: return "SpatialMotionVectorBase_changeCoordFrame"; + case 517: return "SpatialMotionVectorBase_compose"; + case 518: return "SpatialMotionVectorBase_inverse"; + case 519: return "SpatialMotionVectorBase_dot"; + case 520: return "SpatialMotionVectorBase_plus"; + case 521: return "SpatialMotionVectorBase_minus"; + case 522: return "SpatialMotionVectorBase_uminus"; + case 523: return "SpatialMotionVectorBase_Zero"; + case 524: return "SpatialMotionVectorBase_asVector"; + case 525: return "SpatialMotionVectorBase_toString"; + case 526: return "SpatialMotionVectorBase_display"; + case 527: return "SpatialMotionVectorBase_toMatlab"; + case 528: return "SpatialMotionVectorBase_fromMatlab"; + case 529: return "delete_SpatialMotionVectorBase"; + case 530: return "new_SpatialForceVectorBase"; + case 531: return "SpatialForceVectorBase_getLinearVec3"; + case 532: return "SpatialForceVectorBase_getAngularVec3"; + case 533: return "SpatialForceVectorBase_setLinearVec3"; + case 534: return "SpatialForceVectorBase_setAngularVec3"; + case 535: return "SpatialForceVectorBase_paren"; + case 536: return "SpatialForceVectorBase_getVal"; + case 537: return "SpatialForceVectorBase_setVal"; + case 538: return "SpatialForceVectorBase_size"; + case 539: return "SpatialForceVectorBase_zero"; + case 540: return "SpatialForceVectorBase_changePoint"; + case 541: return "SpatialForceVectorBase_changeCoordFrame"; + case 542: return "SpatialForceVectorBase_compose"; + case 543: return "SpatialForceVectorBase_inverse"; + case 544: return "SpatialForceVectorBase_dot"; + case 545: return "SpatialForceVectorBase_plus"; + case 546: return "SpatialForceVectorBase_minus"; + case 547: return "SpatialForceVectorBase_uminus"; + case 548: return "SpatialForceVectorBase_Zero"; + case 549: return "SpatialForceVectorBase_asVector"; + case 550: return "SpatialForceVectorBase_toString"; + case 551: return "SpatialForceVectorBase_display"; + case 552: return "SpatialForceVectorBase_toMatlab"; + case 553: return "SpatialForceVectorBase_fromMatlab"; + case 554: return "delete_SpatialForceVectorBase"; + case 555: return "new_Dummy"; + case 556: return "delete_Dummy"; + case 557: return "new_SpatialMotionVector"; + case 558: return "SpatialMotionVector_mtimes"; + case 559: return "SpatialMotionVector_cross"; + case 560: return "SpatialMotionVector_asCrossProductMatrix"; + case 561: return "SpatialMotionVector_asCrossProductMatrixWrench"; + case 562: return "SpatialMotionVector_exp"; + case 563: return "delete_SpatialMotionVector"; + case 564: return "new_SpatialForceVector"; + case 565: return "delete_SpatialForceVector"; + case 566: return "SpatialForceVector_mtimes"; + case 567: return "new_Twist"; + case 568: return "Twist_plus"; + case 569: return "Twist_minus"; + case 570: return "Twist_uminus"; + case 571: return "Twist_mtimes"; + case 572: return "delete_Twist"; + case 573: return "new_Wrench"; + case 574: return "Wrench_plus"; + case 575: return "Wrench_minus"; + case 576: return "Wrench_uminus"; + case 577: return "delete_Wrench"; + case 578: return "new_SpatialMomentum"; + case 579: return "SpatialMomentum_plus"; + case 580: return "SpatialMomentum_minus"; + case 581: return "SpatialMomentum_uminus"; + case 582: return "delete_SpatialMomentum"; + case 583: return "new_SpatialAcc"; + case 584: return "SpatialAcc_plus"; + case 585: return "SpatialAcc_minus"; + case 586: return "SpatialAcc_uminus"; + case 587: return "delete_SpatialAcc"; + case 588: return "new_ClassicalAcc"; + case 589: return "ClassicalAcc_changeCoordFrame"; + case 590: return "ClassicalAcc_Zero"; + case 591: return "ClassicalAcc_fromSpatial"; + case 592: return "ClassicalAcc_toSpatial"; + case 593: return "delete_ClassicalAcc"; + case 594: return "new_Direction"; + case 595: return "Direction_Normalize"; + case 596: return "Direction_isParallel"; + case 597: return "Direction_isPerpendicular"; + case 598: return "Direction_reverse"; + case 599: return "Direction_toString"; + case 600: return "Direction_display"; + case 601: return "Direction_Default"; + case 602: return "delete_Direction"; + case 603: return "new_Axis"; + case 604: return "Axis_getDirection"; + case 605: return "Axis_getOrigin"; + case 606: return "Axis_setDirection"; + case 607: return "Axis_setOrigin"; + case 608: return "Axis_getRotationTransform"; + case 609: return "Axis_getRotationTransformDerivative"; + case 610: return "Axis_getRotationTwist"; + case 611: return "Axis_getRotationSpatialAcc"; + case 612: return "Axis_getTranslationTransform"; + case 613: return "Axis_getTranslationTransformDerivative"; + case 614: return "Axis_getTranslationTwist"; + case 615: return "Axis_getTranslationSpatialAcc"; + case 616: return "Axis_isParallel"; + case 617: return "Axis_reverse"; + case 618: return "Axis_toString"; + case 619: return "Axis_display"; + case 620: return "delete_Axis"; + case 621: return "new_RotationalInertia"; + case 622: return "RotationalInertia_Zero"; + case 623: return "delete_RotationalInertia"; + case 624: return "new_SpatialInertia"; + case 625: return "SpatialInertia_combine"; + case 626: return "SpatialInertia_fromRotationalInertiaWrtCenterOfMass"; + case 627: return "SpatialInertia_getMass"; + case 628: return "SpatialInertia_getCenterOfMass"; + case 629: return "SpatialInertia_getRotationalInertiaWrtFrameOrigin"; + case 630: return "SpatialInertia_getRotationalInertiaWrtCenterOfMass"; + case 631: return "SpatialInertia_multiply"; + case 632: return "SpatialInertia_zero"; + case 633: return "SpatialInertia_asMatrix"; + case 634: return "SpatialInertia_applyInverse"; + case 635: return "SpatialInertia_getInverse"; + case 636: return "SpatialInertia_plus"; + case 637: return "SpatialInertia_mtimes"; + case 638: return "SpatialInertia_biasWrench"; + case 639: return "SpatialInertia_biasWrenchDerivative"; + case 640: return "SpatialInertia_Zero"; + case 641: return "SpatialInertia_asVector"; + case 642: return "SpatialInertia_fromVector"; + case 643: return "SpatialInertia_isPhysicallyConsistent"; + case 644: return "SpatialInertia_momentumRegressor"; + case 645: return "SpatialInertia_momentumDerivativeRegressor"; + case 646: return "SpatialInertia_momentumDerivativeSlotineLiRegressor"; + case 647: return "delete_SpatialInertia"; + case 648: return "new_ArticulatedBodyInertia"; + case 649: return "ArticulatedBodyInertia_getLinearLinearSubmatrix"; + case 650: return "ArticulatedBodyInertia_getLinearAngularSubmatrix"; + case 651: return "ArticulatedBodyInertia_getAngularAngularSubmatrix"; + case 652: return "ArticulatedBodyInertia_combine"; + case 653: return "ArticulatedBodyInertia_applyInverse"; + case 654: return "ArticulatedBodyInertia_asMatrix"; + case 655: return "ArticulatedBodyInertia_getInverse"; + case 656: return "ArticulatedBodyInertia_plus"; + case 657: return "ArticulatedBodyInertia_minus"; + case 658: return "ArticulatedBodyInertia_mtimes"; + case 659: return "ArticulatedBodyInertia_zero"; + case 660: return "ArticulatedBodyInertia_ABADyadHelper"; + case 661: return "ArticulatedBodyInertia_ABADyadHelperLin"; + case 662: return "delete_ArticulatedBodyInertia"; + case 663: return "RigidBodyInertiaNonLinearParametrization_mass_get"; + case 664: return "RigidBodyInertiaNonLinearParametrization_mass_set"; + case 665: return "RigidBodyInertiaNonLinearParametrization_com_get"; + case 666: return "RigidBodyInertiaNonLinearParametrization_com_set"; + case 667: return "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get"; + case 668: return "RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set"; + case 669: return "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get"; + case 670: return "RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set"; + case 671: return "RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform"; + case 672: return "RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia"; + case 673: return "RigidBodyInertiaNonLinearParametrization_fromInertialParameters"; + case 674: return "RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia"; + case 675: return "RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent"; + case 676: return "RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec"; + case 677: return "RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec"; + case 678: return "RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec"; + case 679: return "new_RigidBodyInertiaNonLinearParametrization"; + case 680: return "delete_RigidBodyInertiaNonLinearParametrization"; + case 681: return "new_Rotation"; + case 682: return "Rotation_changeOrientFrame"; + case 683: return "Rotation_changeRefOrientFrame"; + case 684: return "Rotation_changeCoordinateFrame"; + case 685: return "Rotation_compose"; + case 686: return "Rotation_inverse2"; + case 687: return "Rotation_changeCoordFrameOf"; + case 688: return "Rotation_inverse"; + case 689: return "Rotation_mtimes"; + case 690: return "Rotation_log"; + case 691: return "Rotation_fromQuaternion"; + case 692: return "Rotation_getRPY"; + case 693: return "Rotation_asRPY"; + case 694: return "Rotation_getQuaternion"; + case 695: return "Rotation_asQuaternion"; + case 696: return "Rotation_RotX"; + case 697: return "Rotation_RotY"; + case 698: return "Rotation_RotZ"; + case 699: return "Rotation_RotAxis"; + case 700: return "Rotation_RotAxisDerivative"; + case 701: return "Rotation_RPY"; + case 702: return "Rotation_RPYRightTrivializedDerivative"; + case 703: return "Rotation_RPYRightTrivializedDerivativeRateOfChange"; + case 704: return "Rotation_RPYRightTrivializedDerivativeInverse"; + case 705: return "Rotation_RPYRightTrivializedDerivativeInverseRateOfChange"; + case 706: return "Rotation_QuaternionRightTrivializedDerivative"; + case 707: return "Rotation_QuaternionRightTrivializedDerivativeInverse"; + case 708: return "Rotation_Identity"; + case 709: return "Rotation_RotationFromQuaternion"; + case 710: return "Rotation_leftJacobian"; + case 711: return "Rotation_leftJacobianInverse"; + case 712: return "Rotation_toString"; + case 713: return "Rotation_display"; + case 714: return "delete_Rotation"; + case 715: return "new_Transform"; + case 716: return "Transform_fromHomogeneousTransform"; + case 717: return "Transform_getRotation"; + case 718: return "Transform_getPosition"; + case 719: return "Transform_setRotation"; + case 720: return "Transform_setPosition"; + case 721: return "Transform_compose"; + case 722: return "Transform_inverse2"; + case 723: return "Transform_inverse"; + case 724: return "Transform_mtimes"; + case 725: return "Transform_Identity"; + case 726: return "Transform_asHomogeneousTransform"; + case 727: return "Transform_asAdjointTransform"; + case 728: return "Transform_asAdjointTransformWrench"; + case 729: return "Transform_log"; + case 730: return "Transform_toString"; + case 731: return "Transform_display"; + case 732: return "delete_Transform"; + case 733: return "new_TransformDerivative"; + case 734: return "delete_TransformDerivative"; + case 735: return "TransformDerivative_getRotationDerivative"; + case 736: return "TransformDerivative_getPositionDerivative"; + case 737: return "TransformDerivative_setRotationDerivative"; + case 738: return "TransformDerivative_setPositionDerivative"; + case 739: return "TransformDerivative_Zero"; + case 740: return "TransformDerivative_asHomogeneousTransformDerivative"; + case 741: return "TransformDerivative_asAdjointTransformDerivative"; + case 742: return "TransformDerivative_asAdjointTransformWrenchDerivative"; + case 743: return "TransformDerivative_mtimes"; + case 744: return "TransformDerivative_derivativeOfInverse"; + case 745: return "TransformDerivative_transform"; + case 746: return "dynamic_extent_get"; + case 747: return "DynamicSpan_extent_get"; + case 748: return "new_DynamicSpan"; + case 749: return "delete_DynamicSpan"; + case 750: return "DynamicSpan_first"; + case 751: return "DynamicSpan_last"; + case 752: return "DynamicSpan_subspan"; + case 753: return "DynamicSpan_size"; + case 754: return "DynamicSpan_size_bytes"; + case 755: return "DynamicSpan_empty"; + case 756: return "DynamicSpan_brace"; + case 757: return "DynamicSpan_getVal"; + case 758: return "DynamicSpan_setVal"; + case 759: return "DynamicSpan_at"; + case 760: return "DynamicSpan_paren"; + case 761: return "DynamicSpan_begin"; + case 762: return "DynamicSpan_end"; + case 763: return "DynamicSpan_cbegin"; + case 764: return "DynamicSpan_cend"; + case 765: return "DynamicSpan_rbegin"; + case 766: return "DynamicSpan_rend"; + case 767: return "DynamicSpan_crbegin"; + case 768: return "DynamicSpan_crend"; + case 769: return "new_DynamicMatrixView"; + case 770: return "DynamicMatrixView_storageOrder"; + case 771: return "DynamicMatrixView_paren"; + case 772: return "DynamicMatrixView_rows"; + case 773: return "DynamicMatrixView_cols"; + case 774: return "DynamicMatrixView_block"; + case 775: return "delete_DynamicMatrixView"; + case 776: return "LINK_INVALID_INDEX_get"; + case 777: return "LINK_INVALID_INDEX_set"; + case 778: return "LINK_INVALID_NAME_get"; + case 779: return "LINK_INVALID_NAME_set"; + case 780: return "JOINT_INVALID_INDEX_get"; + case 781: return "JOINT_INVALID_INDEX_set"; + case 782: return "JOINT_INVALID_NAME_get"; + case 783: return "JOINT_INVALID_NAME_set"; + case 784: return "DOF_INVALID_INDEX_get"; + case 785: return "DOF_INVALID_INDEX_set"; + case 786: return "DOF_INVALID_NAME_get"; + case 787: return "DOF_INVALID_NAME_set"; + case 788: return "FRAME_INVALID_INDEX_get"; + case 789: return "FRAME_INVALID_INDEX_set"; + case 790: return "FRAME_INVALID_NAME_get"; + case 791: return "FRAME_INVALID_NAME_set"; + case 792: return "TRAVERSAL_INVALID_INDEX_get"; + case 793: return "TRAVERSAL_INVALID_INDEX_set"; + case 794: return "new_LinkPositions"; + case 795: return "LinkPositions_resize"; + case 796: return "LinkPositions_isConsistent"; + case 797: return "LinkPositions_getNrOfLinks"; + case 798: return "LinkPositions_paren"; + case 799: return "LinkPositions_toString"; + case 800: return "delete_LinkPositions"; + case 801: return "new_LinkWrenches"; + case 802: return "LinkWrenches_resize"; + case 803: return "LinkWrenches_isConsistent"; + case 804: return "LinkWrenches_getNrOfLinks"; + case 805: return "LinkWrenches_paren"; + case 806: return "LinkWrenches_toString"; + case 807: return "LinkWrenches_zero"; + case 808: return "delete_LinkWrenches"; + case 809: return "new_LinkInertias"; + case 810: return "LinkInertias_resize"; + case 811: return "LinkInertias_isConsistent"; + case 812: return "LinkInertias_paren"; + case 813: return "delete_LinkInertias"; + case 814: return "new_LinkArticulatedBodyInertias"; + case 815: return "LinkArticulatedBodyInertias_resize"; + case 816: return "LinkArticulatedBodyInertias_isConsistent"; + case 817: return "LinkArticulatedBodyInertias_paren"; + case 818: return "delete_LinkArticulatedBodyInertias"; + case 819: return "new_LinkVelArray"; + case 820: return "LinkVelArray_resize"; + case 821: return "LinkVelArray_isConsistent"; + case 822: return "LinkVelArray_getNrOfLinks"; + case 823: return "LinkVelArray_paren"; + case 824: return "LinkVelArray_toString"; + case 825: return "delete_LinkVelArray"; + case 826: return "new_LinkAccArray"; + case 827: return "LinkAccArray_resize"; + case 828: return "LinkAccArray_isConsistent"; + case 829: return "LinkAccArray_paren"; + case 830: return "LinkAccArray_getNrOfLinks"; + case 831: return "LinkAccArray_toString"; + case 832: return "delete_LinkAccArray"; + case 833: return "new_Link"; + case 834: return "Link_inertia"; + case 835: return "Link_setInertia"; + case 836: return "Link_getInertia"; + case 837: return "Link_setIndex"; + case 838: return "Link_getIndex"; + case 839: return "delete_Link"; + case 840: return "delete_IJoint"; + case 841: return "IJoint_clone"; + case 842: return "IJoint_getNrOfPosCoords"; + case 843: return "IJoint_getNrOfDOFs"; + case 844: return "IJoint_setAttachedLinks"; + case 845: return "IJoint_setRestTransform"; + case 846: return "IJoint_getFirstAttachedLink"; + case 847: return "IJoint_getSecondAttachedLink"; + case 848: return "IJoint_getRestTransform"; + case 849: return "IJoint_getTransform"; + case 850: return "IJoint_getTransformDerivative"; + case 851: return "IJoint_getMotionSubspaceVector"; + case 852: return "IJoint_computeChildPosVelAcc"; + case 853: return "IJoint_computeChildVelAcc"; + case 854: return "IJoint_computeChildVel"; + case 855: return "IJoint_computeChildAcc"; + case 856: return "IJoint_computeChildBiasAcc"; + case 857: return "IJoint_computeJointTorque"; + case 858: return "IJoint_setIndex"; + case 859: return "IJoint_getIndex"; + case 860: return "IJoint_setPosCoordsOffset"; + case 861: return "IJoint_getPosCoordsOffset"; + case 862: return "IJoint_setDOFsOffset"; + case 863: return "IJoint_getDOFsOffset"; + case 864: return "IJoint_hasPosLimits"; + case 865: return "IJoint_enablePosLimits"; + case 866: return "IJoint_getPosLimits"; + case 867: return "IJoint_getMinPosLimit"; + case 868: return "IJoint_getMaxPosLimit"; + case 869: return "IJoint_setPosLimits"; + case 870: return "IJoint_getJointDynamicsType"; + case 871: return "IJoint_setJointDynamicsType"; + case 872: return "IJoint_setDamping"; + case 873: return "IJoint_setStaticFriction"; + case 874: return "IJoint_getDamping"; + case 875: return "IJoint_getStaticFriction"; + case 876: return "IJoint_isRevoluteJoint"; + case 877: return "IJoint_isFixedJoint"; + case 878: return "IJoint_isPrismaticJoint"; + case 879: return "IJoint_asRevoluteJoint"; + case 880: return "IJoint_asFixedJoint"; + case 881: return "IJoint_asPrismaticJoint"; + case 882: return "new_FixedJoint"; + case 883: return "delete_FixedJoint"; + case 884: return "FixedJoint_clone"; + case 885: return "FixedJoint_getNrOfPosCoords"; + case 886: return "FixedJoint_getNrOfDOFs"; + case 887: return "FixedJoint_setAttachedLinks"; + case 888: return "FixedJoint_setRestTransform"; + case 889: return "FixedJoint_getFirstAttachedLink"; + case 890: return "FixedJoint_getSecondAttachedLink"; + case 891: return "FixedJoint_getRestTransform"; + case 892: return "FixedJoint_getTransform"; + case 893: return "FixedJoint_getTransformDerivative"; + case 894: return "FixedJoint_getMotionSubspaceVector"; + case 895: return "FixedJoint_computeChildPosVelAcc"; + case 896: return "FixedJoint_computeChildVelAcc"; + case 897: return "FixedJoint_computeChildVel"; + case 898: return "FixedJoint_computeChildAcc"; + case 899: return "FixedJoint_computeChildBiasAcc"; + case 900: return "FixedJoint_computeJointTorque"; + case 901: return "FixedJoint_setIndex"; + case 902: return "FixedJoint_getIndex"; + case 903: return "FixedJoint_setPosCoordsOffset"; + case 904: return "FixedJoint_getPosCoordsOffset"; + case 905: return "FixedJoint_setDOFsOffset"; + case 906: return "FixedJoint_getDOFsOffset"; + case 907: return "FixedJoint_hasPosLimits"; + case 908: return "FixedJoint_enablePosLimits"; + case 909: return "FixedJoint_getPosLimits"; + case 910: return "FixedJoint_getMinPosLimit"; + case 911: return "FixedJoint_getMaxPosLimit"; + case 912: return "FixedJoint_setPosLimits"; + case 913: return "FixedJoint_getJointDynamicsType"; + case 914: return "FixedJoint_setJointDynamicsType"; + case 915: return "FixedJoint_getDamping"; + case 916: return "FixedJoint_getStaticFriction"; + case 917: return "FixedJoint_setDamping"; + case 918: return "FixedJoint_setStaticFriction"; + case 919: return "delete_MovableJointImpl1"; + case 920: return "MovableJointImpl1_getNrOfPosCoords"; + case 921: return "MovableJointImpl1_getNrOfDOFs"; + case 922: return "MovableJointImpl1_setIndex"; + case 923: return "MovableJointImpl1_getIndex"; + case 924: return "MovableJointImpl1_setPosCoordsOffset"; + case 925: return "MovableJointImpl1_getPosCoordsOffset"; + case 926: return "MovableJointImpl1_setDOFsOffset"; + case 927: return "MovableJointImpl1_getDOFsOffset"; + case 928: return "delete_MovableJointImpl2"; + case 929: return "MovableJointImpl2_getNrOfPosCoords"; + case 930: return "MovableJointImpl2_getNrOfDOFs"; + case 931: return "MovableJointImpl2_setIndex"; + case 932: return "MovableJointImpl2_getIndex"; + case 933: return "MovableJointImpl2_setPosCoordsOffset"; + case 934: return "MovableJointImpl2_getPosCoordsOffset"; + case 935: return "MovableJointImpl2_setDOFsOffset"; + case 936: return "MovableJointImpl2_getDOFsOffset"; + case 937: return "delete_MovableJointImpl3"; + case 938: return "MovableJointImpl3_getNrOfPosCoords"; + case 939: return "MovableJointImpl3_getNrOfDOFs"; + case 940: return "MovableJointImpl3_setIndex"; + case 941: return "MovableJointImpl3_getIndex"; + case 942: return "MovableJointImpl3_setPosCoordsOffset"; + case 943: return "MovableJointImpl3_getPosCoordsOffset"; + case 944: return "MovableJointImpl3_setDOFsOffset"; + case 945: return "MovableJointImpl3_getDOFsOffset"; + case 946: return "delete_MovableJointImpl4"; + case 947: return "MovableJointImpl4_getNrOfPosCoords"; + case 948: return "MovableJointImpl4_getNrOfDOFs"; + case 949: return "MovableJointImpl4_setIndex"; + case 950: return "MovableJointImpl4_getIndex"; + case 951: return "MovableJointImpl4_setPosCoordsOffset"; + case 952: return "MovableJointImpl4_getPosCoordsOffset"; + case 953: return "MovableJointImpl4_setDOFsOffset"; + case 954: return "MovableJointImpl4_getDOFsOffset"; + case 955: return "delete_MovableJointImpl5"; + case 956: return "MovableJointImpl5_getNrOfPosCoords"; + case 957: return "MovableJointImpl5_getNrOfDOFs"; + case 958: return "MovableJointImpl5_setIndex"; + case 959: return "MovableJointImpl5_getIndex"; + case 960: return "MovableJointImpl5_setPosCoordsOffset"; + case 961: return "MovableJointImpl5_getPosCoordsOffset"; + case 962: return "MovableJointImpl5_setDOFsOffset"; + case 963: return "MovableJointImpl5_getDOFsOffset"; + case 964: return "delete_MovableJointImpl6"; + case 965: return "MovableJointImpl6_getNrOfPosCoords"; + case 966: return "MovableJointImpl6_getNrOfDOFs"; + case 967: return "MovableJointImpl6_setIndex"; + case 968: return "MovableJointImpl6_getIndex"; + case 969: return "MovableJointImpl6_setPosCoordsOffset"; + case 970: return "MovableJointImpl6_getPosCoordsOffset"; + case 971: return "MovableJointImpl6_setDOFsOffset"; + case 972: return "MovableJointImpl6_getDOFsOffset"; + case 973: return "new_RevoluteJoint"; + case 974: return "delete_RevoluteJoint"; + case 975: return "RevoluteJoint_clone"; + case 976: return "RevoluteJoint_setAttachedLinks"; + case 977: return "RevoluteJoint_setRestTransform"; + case 978: return "RevoluteJoint_setAxis"; + case 979: return "RevoluteJoint_getFirstAttachedLink"; + case 980: return "RevoluteJoint_getSecondAttachedLink"; + case 981: return "RevoluteJoint_getAxis"; + case 982: return "RevoluteJoint_getRestTransform"; + case 983: return "RevoluteJoint_getTransform"; + case 984: return "RevoluteJoint_getTransformDerivative"; + case 985: return "RevoluteJoint_getMotionSubspaceVector"; + case 986: return "RevoluteJoint_computeChildPosVelAcc"; + case 987: return "RevoluteJoint_computeChildVel"; + case 988: return "RevoluteJoint_computeChildVelAcc"; + case 989: return "RevoluteJoint_computeChildAcc"; + case 990: return "RevoluteJoint_computeChildBiasAcc"; + case 991: return "RevoluteJoint_computeJointTorque"; + case 992: return "RevoluteJoint_hasPosLimits"; + case 993: return "RevoluteJoint_enablePosLimits"; + case 994: return "RevoluteJoint_getPosLimits"; + case 995: return "RevoluteJoint_getMinPosLimit"; + case 996: return "RevoluteJoint_getMaxPosLimit"; + case 997: return "RevoluteJoint_setPosLimits"; + case 998: return "RevoluteJoint_getJointDynamicsType"; + case 999: return "RevoluteJoint_setJointDynamicsType"; + case 1000: return "RevoluteJoint_getDamping"; + case 1001: return "RevoluteJoint_getStaticFriction"; + case 1002: return "RevoluteJoint_setDamping"; + case 1003: return "RevoluteJoint_setStaticFriction"; + case 1004: return "new_PrismaticJoint"; + case 1005: return "delete_PrismaticJoint"; + case 1006: return "PrismaticJoint_clone"; + case 1007: return "PrismaticJoint_setAttachedLinks"; + case 1008: return "PrismaticJoint_setRestTransform"; + case 1009: return "PrismaticJoint_setAxis"; + case 1010: return "PrismaticJoint_getFirstAttachedLink"; + case 1011: return "PrismaticJoint_getSecondAttachedLink"; + case 1012: return "PrismaticJoint_getAxis"; + case 1013: return "PrismaticJoint_getRestTransform"; + case 1014: return "PrismaticJoint_getTransform"; + case 1015: return "PrismaticJoint_getTransformDerivative"; + case 1016: return "PrismaticJoint_getMotionSubspaceVector"; + case 1017: return "PrismaticJoint_computeChildPosVelAcc"; + case 1018: return "PrismaticJoint_computeChildVel"; + case 1019: return "PrismaticJoint_computeChildVelAcc"; + case 1020: return "PrismaticJoint_computeChildAcc"; + case 1021: return "PrismaticJoint_computeChildBiasAcc"; + case 1022: return "PrismaticJoint_computeJointTorque"; + case 1023: return "PrismaticJoint_hasPosLimits"; + case 1024: return "PrismaticJoint_enablePosLimits"; + case 1025: return "PrismaticJoint_getPosLimits"; + case 1026: return "PrismaticJoint_getMinPosLimit"; + case 1027: return "PrismaticJoint_getMaxPosLimit"; + case 1028: return "PrismaticJoint_setPosLimits"; + case 1029: return "PrismaticJoint_getJointDynamicsType"; + case 1030: return "PrismaticJoint_setJointDynamicsType"; + case 1031: return "PrismaticJoint_getDamping"; + case 1032: return "PrismaticJoint_getStaticFriction"; + case 1033: return "PrismaticJoint_setDamping"; + case 1034: return "PrismaticJoint_setStaticFriction"; + case 1035: return "new_Traversal"; + case 1036: return "delete_Traversal"; + case 1037: return "Traversal_getNrOfVisitedLinks"; + case 1038: return "Traversal_getLink"; + case 1039: return "Traversal_getBaseLink"; + case 1040: return "Traversal_getParentLink"; + case 1041: return "Traversal_getParentJoint"; + case 1042: return "Traversal_getParentLinkFromLinkIndex"; + case 1043: return "Traversal_getParentJointFromLinkIndex"; + case 1044: return "Traversal_getTraversalIndexFromLinkIndex"; + case 1045: return "Traversal_reset"; + case 1046: return "Traversal_addTraversalBase"; + case 1047: return "Traversal_addTraversalElement"; + case 1048: return "Traversal_isParentOf"; + case 1049: return "Traversal_getChildLinkIndexFromJointIndex"; + case 1050: return "Traversal_getParentLinkIndexFromJointIndex"; + case 1051: return "Traversal_toString"; + case 1052: return "new_Material"; + case 1053: return "Material_name"; + case 1054: return "Material_hasColor"; + case 1055: return "Material_color"; + case 1056: return "Material_setColor"; + case 1057: return "Material_hasTexture"; + case 1058: return "Material_texture"; + case 1059: return "Material_setTexture"; + case 1060: return "delete_Material"; + case 1061: return "delete_SolidShape"; + case 1062: return "SolidShape_clone"; + case 1063: return "SolidShape_getName"; + case 1064: return "SolidShape_setName"; + case 1065: return "SolidShape_isNameValid"; + case 1066: return "SolidShape_getLink_H_geometry"; + case 1067: return "SolidShape_setLink_H_geometry"; + case 1068: return "SolidShape_isMaterialSet"; + case 1069: return "SolidShape_getMaterial"; + case 1070: return "SolidShape_setMaterial"; + case 1071: return "SolidShape_isSphere"; + case 1072: return "SolidShape_isBox"; + case 1073: return "SolidShape_isCylinder"; + case 1074: return "SolidShape_isExternalMesh"; + case 1075: return "SolidShape_asSphere"; + case 1076: return "SolidShape_asBox"; + case 1077: return "SolidShape_asCylinder"; + case 1078: return "SolidShape_asExternalMesh"; + case 1079: return "delete_Sphere"; + case 1080: return "Sphere_clone"; + case 1081: return "Sphere_getRadius"; + case 1082: return "Sphere_setRadius"; + case 1083: return "new_Sphere"; + case 1084: return "delete_Box"; + case 1085: return "Box_clone"; + case 1086: return "Box_getX"; + case 1087: return "Box_setX"; + case 1088: return "Box_getY"; + case 1089: return "Box_setY"; + case 1090: return "Box_getZ"; + case 1091: return "Box_setZ"; + case 1092: return "new_Box"; + case 1093: return "delete_Cylinder"; + case 1094: return "Cylinder_clone"; + case 1095: return "Cylinder_getLength"; + case 1096: return "Cylinder_setLength"; + case 1097: return "Cylinder_getRadius"; + case 1098: return "Cylinder_setRadius"; + case 1099: return "new_Cylinder"; + case 1100: return "delete_ExternalMesh"; + case 1101: return "ExternalMesh_clone"; + case 1102: return "ExternalMesh_getFilename"; + case 1103: return "ExternalMesh_getPackageDirs"; + case 1104: return "ExternalMesh_getFileLocationOnLocalFileSystem"; + case 1105: return "ExternalMesh_setFilename"; + case 1106: return "ExternalMesh_setPackageDirs"; + case 1107: return "ExternalMesh_getScale"; + case 1108: return "ExternalMesh_setScale"; + case 1109: return "new_ExternalMesh"; + case 1110: return "delete_ModelSolidShapes"; + case 1111: return "new_ModelSolidShapes"; + case 1112: return "ModelSolidShapes_clear"; + case 1113: return "ModelSolidShapes_resize"; + case 1114: return "ModelSolidShapes_isConsistent"; + case 1115: return "ModelSolidShapes_getLinkSolidShapes"; + case 1116: return "NR_OF_SENSOR_TYPES_get"; + case 1117: return "_wrap_isLinkSensor"; + case 1118: return "_wrap_isJointSensor"; + case 1119: return "_wrap_getSensorTypeSize"; + case 1120: return "delete_Sensor"; + case 1121: return "Sensor_getName"; + case 1122: return "Sensor_getSensorType"; + case 1123: return "Sensor_isValid"; + case 1124: return "Sensor_setName"; + case 1125: return "Sensor_clone"; + case 1126: return "Sensor_isConsistent"; + case 1127: return "Sensor_updateIndices"; + case 1128: return "delete_JointSensor"; + case 1129: return "JointSensor_getParentJoint"; + case 1130: return "JointSensor_getParentJointIndex"; + case 1131: return "JointSensor_setParentJoint"; + case 1132: return "JointSensor_setParentJointIndex"; + case 1133: return "JointSensor_isConsistent"; + case 1134: return "delete_LinkSensor"; + case 1135: return "LinkSensor_getParentLink"; + case 1136: return "LinkSensor_getParentLinkIndex"; + case 1137: return "LinkSensor_getLinkSensorTransform"; + case 1138: return "LinkSensor_setParentLink"; + case 1139: return "LinkSensor_setParentLinkIndex"; + case 1140: return "LinkSensor_setLinkSensorTransform"; + case 1141: return "LinkSensor_isConsistent"; + case 1142: return "new_SensorsList"; + case 1143: return "delete_SensorsList"; + case 1144: return "SensorsList_addSensor"; + case 1145: return "SensorsList_setSerialization"; + case 1146: return "SensorsList_getSerialization"; + case 1147: return "SensorsList_getNrOfSensors"; + case 1148: return "SensorsList_getSensorIndex"; + case 1149: return "SensorsList_getSizeOfAllSensorsMeasurements"; + case 1150: return "SensorsList_getSensor"; + case 1151: return "SensorsList_isConsistent"; + case 1152: return "SensorsList_removeSensor"; + case 1153: return "SensorsList_removeAllSensorsOfType"; + case 1154: return "SensorsList_getSixAxisForceTorqueSensor"; + case 1155: return "SensorsList_getAccelerometerSensor"; + case 1156: return "SensorsList_getGyroscopeSensor"; + case 1157: return "SensorsList_getThreeAxisAngularAccelerometerSensor"; + case 1158: return "SensorsList_getThreeAxisForceTorqueContactSensor"; + case 1159: return "new_SensorsMeasurements"; + case 1160: return "delete_SensorsMeasurements"; + case 1161: return "SensorsMeasurements_setNrOfSensors"; + case 1162: return "SensorsMeasurements_getNrOfSensors"; + case 1163: return "SensorsMeasurements_resize"; + case 1164: return "SensorsMeasurements_toVector"; + case 1165: return "SensorsMeasurements_setMeasurement"; + case 1166: return "SensorsMeasurements_getMeasurement"; + case 1167: return "SensorsMeasurements_getSizeOfAllSensorsMeasurements"; + case 1168: return "Neighbor_neighborLink_get"; + case 1169: return "Neighbor_neighborLink_set"; + case 1170: return "Neighbor_neighborJoint_get"; + case 1171: return "Neighbor_neighborJoint_set"; + case 1172: return "new_Neighbor"; + case 1173: return "delete_Neighbor"; + case 1174: return "new_Model"; + case 1175: return "Model_copy"; + case 1176: return "delete_Model"; + case 1177: return "Model_getNrOfLinks"; + case 1178: return "Model_getPackageDirs"; + case 1179: return "Model_setPackageDirs"; + case 1180: return "Model_getLinkName"; + case 1181: return "Model_getLinkIndex"; + case 1182: return "Model_isValidLinkIndex"; + case 1183: return "Model_getLink"; + case 1184: return "Model_addLink"; + case 1185: return "Model_getNrOfJoints"; + case 1186: return "Model_getJointName"; + case 1187: return "Model_getTotalMass"; + case 1188: return "Model_getJointIndex"; + case 1189: return "Model_getJoint"; + case 1190: return "Model_isValidJointIndex"; + case 1191: return "Model_isLinkNameUsed"; + case 1192: return "Model_isJointNameUsed"; + case 1193: return "Model_isFrameNameUsed"; + case 1194: return "Model_addJoint"; + case 1195: return "Model_addJointAndLink"; + case 1196: return "Model_insertLinkToExistingJointAndAddJointForDisplacedLink"; + case 1197: return "Model_getNrOfPosCoords"; + case 1198: return "Model_getNrOfDOFs"; + case 1199: return "Model_getNrOfFrames"; + case 1200: return "Model_addAdditionalFrameToLink"; + case 1201: return "Model_getFrameName"; + case 1202: return "Model_getFrameIndex"; + case 1203: return "Model_isValidFrameIndex"; + case 1204: return "Model_getFrameTransform"; + case 1205: return "Model_getFrameLink"; + case 1206: return "Model_getLinkAdditionalFrames"; + case 1207: return "Model_getNrOfNeighbors"; + case 1208: return "Model_getNeighbor"; + case 1209: return "Model_setDefaultBaseLink"; + case 1210: return "Model_getDefaultBaseLink"; + case 1211: return "Model_computeFullTreeTraversal"; + case 1212: return "Model_getInertialParameters"; + case 1213: return "Model_updateInertialParameters"; + case 1214: return "Model_visualSolidShapes"; + case 1215: return "Model_collisionSolidShapes"; + case 1216: return "Model_sensors"; + case 1217: return "Model_toString"; + case 1218: return "Model_isValid"; + case 1219: return "new_JointPosDoubleArray"; + case 1220: return "JointPosDoubleArray_resize"; + case 1221: return "JointPosDoubleArray_isConsistent"; + case 1222: return "delete_JointPosDoubleArray"; + case 1223: return "new_JointDOFsDoubleArray"; + case 1224: return "JointDOFsDoubleArray_resize"; + case 1225: return "JointDOFsDoubleArray_isConsistent"; + case 1226: return "delete_JointDOFsDoubleArray"; + case 1227: return "new_DOFSpatialForceArray"; + case 1228: return "DOFSpatialForceArray_resize"; + case 1229: return "DOFSpatialForceArray_isConsistent"; + case 1230: return "DOFSpatialForceArray_paren"; + case 1231: return "delete_DOFSpatialForceArray"; + case 1232: return "new_DOFSpatialMotionArray"; + case 1233: return "DOFSpatialMotionArray_resize"; + case 1234: return "DOFSpatialMotionArray_isConsistent"; + case 1235: return "DOFSpatialMotionArray_paren"; + case 1236: return "delete_DOFSpatialMotionArray"; + case 1237: return "new_FrameFreeFloatingJacobian"; + case 1238: return "FrameFreeFloatingJacobian_resize"; + case 1239: return "FrameFreeFloatingJacobian_isConsistent"; + case 1240: return "delete_FrameFreeFloatingJacobian"; + case 1241: return "new_MomentumFreeFloatingJacobian"; + case 1242: return "MomentumFreeFloatingJacobian_resize"; + case 1243: return "MomentumFreeFloatingJacobian_isConsistent"; + case 1244: return "delete_MomentumFreeFloatingJacobian"; + case 1245: return "new_FreeFloatingMassMatrix"; + case 1246: return "FreeFloatingMassMatrix_resize"; + case 1247: return "delete_FreeFloatingMassMatrix"; + case 1248: return "new_FreeFloatingPos"; + case 1249: return "FreeFloatingPos_resize"; + case 1250: return "FreeFloatingPos_worldBasePos"; + case 1251: return "FreeFloatingPos_jointPos"; + case 1252: return "FreeFloatingPos_getNrOfPosCoords"; + case 1253: return "delete_FreeFloatingPos"; + case 1254: return "new_FreeFloatingGeneralizedTorques"; + case 1255: return "FreeFloatingGeneralizedTorques_resize"; + case 1256: return "FreeFloatingGeneralizedTorques_baseWrench"; + case 1257: return "FreeFloatingGeneralizedTorques_jointTorques"; + case 1258: return "FreeFloatingGeneralizedTorques_getNrOfDOFs"; + case 1259: return "delete_FreeFloatingGeneralizedTorques"; + case 1260: return "new_FreeFloatingVel"; + case 1261: return "FreeFloatingVel_resize"; + case 1262: return "FreeFloatingVel_baseVel"; + case 1263: return "FreeFloatingVel_jointVel"; + case 1264: return "FreeFloatingVel_getNrOfDOFs"; + case 1265: return "delete_FreeFloatingVel"; + case 1266: return "new_FreeFloatingAcc"; + case 1267: return "FreeFloatingAcc_resize"; + case 1268: return "FreeFloatingAcc_baseAcc"; + case 1269: return "FreeFloatingAcc_jointAcc"; + case 1270: return "FreeFloatingAcc_getNrOfDOFs"; + case 1271: return "delete_FreeFloatingAcc"; + case 1272: return "ContactWrench_contactId"; + case 1273: return "ContactWrench_contactPoint"; + case 1274: return "ContactWrench_contactWrench"; + case 1275: return "new_ContactWrench"; + case 1276: return "delete_ContactWrench"; + case 1277: return "new_LinkContactWrenches"; + case 1278: return "LinkContactWrenches_resize"; + case 1279: return "LinkContactWrenches_getNrOfContactsForLink"; + case 1280: return "LinkContactWrenches_setNrOfContactsForLink"; + case 1281: return "LinkContactWrenches_getNrOfLinks"; + case 1282: return "LinkContactWrenches_contactWrench"; + case 1283: return "LinkContactWrenches_computeNetWrenches"; + case 1284: return "LinkContactWrenches_toString"; + case 1285: return "delete_LinkContactWrenches"; + case 1286: return "_wrap_getRandomLink"; + case 1287: return "_wrap_addRandomLinkToModel"; + case 1288: return "_wrap_addRandomAdditionalFrameToModel"; + case 1289: return "_wrap_getRandomLinkIndexOfModel"; + case 1290: return "_wrap_getRandomLinkOfModel"; + case 1291: return "_wrap_int2string"; + case 1292: return "_wrap_getRandomModel"; + case 1293: return "_wrap_getRandomChain"; + case 1294: return "_wrap_getRandomJointPositions"; + case 1295: return "_wrap_getRandomInverseDynamicsInputs"; + case 1296: return "_wrap_removeFakeLinks"; + case 1297: return "_wrap_createReducedModel"; + case 1298: return "_wrap_createModelWithNormalizedJointNumbering"; + case 1299: return "_wrap_extractSubModel"; + case 1300: return "new_SubModelDecomposition"; + case 1301: return "delete_SubModelDecomposition"; + case 1302: return "SubModelDecomposition_splitModelAlongJoints"; + case 1303: return "SubModelDecomposition_setNrOfSubModels"; + case 1304: return "SubModelDecomposition_getNrOfSubModels"; + case 1305: return "SubModelDecomposition_getNrOfLinks"; + case 1306: return "SubModelDecomposition_getTraversal"; + case 1307: return "SubModelDecomposition_getSubModelOfLink"; + case 1308: return "SubModelDecomposition_getSubModelOfFrame"; + case 1309: return "_wrap_computeTransformToTraversalBase"; + case 1310: return "_wrap_computeTransformToSubModelBase"; + case 1311: return "new_SixAxisForceTorqueSensor"; + case 1312: return "delete_SixAxisForceTorqueSensor"; + case 1313: return "SixAxisForceTorqueSensor_setName"; + case 1314: return "SixAxisForceTorqueSensor_setFirstLinkSensorTransform"; + case 1315: return "SixAxisForceTorqueSensor_setSecondLinkSensorTransform"; + case 1316: return "SixAxisForceTorqueSensor_getFirstLinkIndex"; + case 1317: return "SixAxisForceTorqueSensor_getSecondLinkIndex"; + case 1318: return "SixAxisForceTorqueSensor_setFirstLinkName"; + case 1319: return "SixAxisForceTorqueSensor_setSecondLinkName"; + case 1320: return "SixAxisForceTorqueSensor_getFirstLinkName"; + case 1321: return "SixAxisForceTorqueSensor_getSecondLinkName"; + case 1322: return "SixAxisForceTorqueSensor_setParentJoint"; + case 1323: return "SixAxisForceTorqueSensor_setParentJointIndex"; + case 1324: return "SixAxisForceTorqueSensor_setAppliedWrenchLink"; + case 1325: return "SixAxisForceTorqueSensor_getName"; + case 1326: return "SixAxisForceTorqueSensor_getSensorType"; + case 1327: return "SixAxisForceTorqueSensor_getParentJoint"; + case 1328: return "SixAxisForceTorqueSensor_getParentJointIndex"; + case 1329: return "SixAxisForceTorqueSensor_isValid"; + case 1330: return "SixAxisForceTorqueSensor_clone"; + case 1331: return "SixAxisForceTorqueSensor_updateIndices"; + case 1332: return "SixAxisForceTorqueSensor_getAppliedWrenchLink"; + case 1333: return "SixAxisForceTorqueSensor_isLinkAttachedToSensor"; + case 1334: return "SixAxisForceTorqueSensor_getLinkSensorTransform"; + case 1335: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLink"; + case 1336: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix"; + case 1337: return "SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix"; + case 1338: return "SixAxisForceTorqueSensor_predictMeasurement"; + case 1339: return "SixAxisForceTorqueSensor_toString"; + case 1340: return "new_AccelerometerSensor"; + case 1341: return "delete_AccelerometerSensor"; + case 1342: return "AccelerometerSensor_setName"; + case 1343: return "AccelerometerSensor_setLinkSensorTransform"; + case 1344: return "AccelerometerSensor_setParentLink"; + case 1345: return "AccelerometerSensor_setParentLinkIndex"; + case 1346: return "AccelerometerSensor_getName"; + case 1347: return "AccelerometerSensor_getSensorType"; + case 1348: return "AccelerometerSensor_getParentLink"; + case 1349: return "AccelerometerSensor_getParentLinkIndex"; + case 1350: return "AccelerometerSensor_getLinkSensorTransform"; + case 1351: return "AccelerometerSensor_isValid"; + case 1352: return "AccelerometerSensor_clone"; + case 1353: return "AccelerometerSensor_updateIndices"; + case 1354: return "AccelerometerSensor_predictMeasurement"; + case 1355: return "new_GyroscopeSensor"; + case 1356: return "delete_GyroscopeSensor"; + case 1357: return "GyroscopeSensor_setName"; + case 1358: return "GyroscopeSensor_setLinkSensorTransform"; + case 1359: return "GyroscopeSensor_setParentLink"; + case 1360: return "GyroscopeSensor_setParentLinkIndex"; + case 1361: return "GyroscopeSensor_getName"; + case 1362: return "GyroscopeSensor_getSensorType"; + case 1363: return "GyroscopeSensor_getParentLink"; + case 1364: return "GyroscopeSensor_getParentLinkIndex"; + case 1365: return "GyroscopeSensor_getLinkSensorTransform"; + case 1366: return "GyroscopeSensor_isValid"; + case 1367: return "GyroscopeSensor_clone"; + case 1368: return "GyroscopeSensor_updateIndices"; + case 1369: return "GyroscopeSensor_predictMeasurement"; + case 1370: return "new_ThreeAxisAngularAccelerometerSensor"; + case 1371: return "delete_ThreeAxisAngularAccelerometerSensor"; + case 1372: return "ThreeAxisAngularAccelerometerSensor_setName"; + case 1373: return "ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform"; + case 1374: return "ThreeAxisAngularAccelerometerSensor_setParentLink"; + case 1375: return "ThreeAxisAngularAccelerometerSensor_setParentLinkIndex"; + case 1376: return "ThreeAxisAngularAccelerometerSensor_getName"; + case 1377: return "ThreeAxisAngularAccelerometerSensor_getSensorType"; + case 1378: return "ThreeAxisAngularAccelerometerSensor_getParentLink"; + case 1379: return "ThreeAxisAngularAccelerometerSensor_getParentLinkIndex"; + case 1380: return "ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform"; + case 1381: return "ThreeAxisAngularAccelerometerSensor_isValid"; + case 1382: return "ThreeAxisAngularAccelerometerSensor_clone"; + case 1383: return "ThreeAxisAngularAccelerometerSensor_updateIndices"; + case 1384: return "ThreeAxisAngularAccelerometerSensor_predictMeasurement"; + case 1385: return "new_ThreeAxisForceTorqueContactSensor"; + case 1386: return "delete_ThreeAxisForceTorqueContactSensor"; + case 1387: return "ThreeAxisForceTorqueContactSensor_setName"; + case 1388: return "ThreeAxisForceTorqueContactSensor_setLinkSensorTransform"; + case 1389: return "ThreeAxisForceTorqueContactSensor_setParentLink"; + case 1390: return "ThreeAxisForceTorqueContactSensor_setParentLinkIndex"; + case 1391: return "ThreeAxisForceTorqueContactSensor_getName"; + case 1392: return "ThreeAxisForceTorqueContactSensor_getSensorType"; + case 1393: return "ThreeAxisForceTorqueContactSensor_getParentLink"; + case 1394: return "ThreeAxisForceTorqueContactSensor_getParentLinkIndex"; + case 1395: return "ThreeAxisForceTorqueContactSensor_getLinkSensorTransform"; + case 1396: return "ThreeAxisForceTorqueContactSensor_isValid"; + case 1397: return "ThreeAxisForceTorqueContactSensor_clone"; + case 1398: return "ThreeAxisForceTorqueContactSensor_updateIndices"; + case 1399: return "ThreeAxisForceTorqueContactSensor_setLoadCellLocations"; + case 1400: return "ThreeAxisForceTorqueContactSensor_getLoadCellLocations"; + case 1401: return "ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements"; + case 1402: return "ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements"; + case 1403: return "_wrap_predictSensorsMeasurements"; + case 1404: return "_wrap_predictSensorsMeasurementsFromRawBuffers"; + case 1405: return "SolidShapesVector_pop"; + case 1406: return "SolidShapesVector_brace"; + case 1407: return "SolidShapesVector_setbrace"; + case 1408: return "SolidShapesVector_append"; + case 1409: return "SolidShapesVector_empty"; + case 1410: return "SolidShapesVector_size"; + case 1411: return "SolidShapesVector_swap"; + case 1412: return "SolidShapesVector_begin"; + case 1413: return "SolidShapesVector_end"; + case 1414: return "SolidShapesVector_rbegin"; + case 1415: return "SolidShapesVector_rend"; + case 1416: return "SolidShapesVector_clear"; + case 1417: return "SolidShapesVector_get_allocator"; + case 1418: return "SolidShapesVector_pop_back"; + case 1419: return "SolidShapesVector_erase"; + case 1420: return "new_SolidShapesVector"; + case 1421: return "SolidShapesVector_push_back"; + case 1422: return "SolidShapesVector_front"; + case 1423: return "SolidShapesVector_back"; + case 1424: return "SolidShapesVector_assign"; + case 1425: return "SolidShapesVector_resize"; + case 1426: return "SolidShapesVector_insert"; + case 1427: return "SolidShapesVector_reserve"; + case 1428: return "SolidShapesVector_capacity"; + case 1429: return "delete_SolidShapesVector"; + case 1430: return "LinksSolidShapesVector_pop"; + case 1431: return "LinksSolidShapesVector_brace"; + case 1432: return "LinksSolidShapesVector_setbrace"; + case 1433: return "LinksSolidShapesVector_append"; + case 1434: return "LinksSolidShapesVector_empty"; + case 1435: return "LinksSolidShapesVector_size"; + case 1436: return "LinksSolidShapesVector_swap"; + case 1437: return "LinksSolidShapesVector_begin"; + case 1438: return "LinksSolidShapesVector_end"; + case 1439: return "LinksSolidShapesVector_rbegin"; + case 1440: return "LinksSolidShapesVector_rend"; + case 1441: return "LinksSolidShapesVector_clear"; + case 1442: return "LinksSolidShapesVector_get_allocator"; + case 1443: return "LinksSolidShapesVector_pop_back"; + case 1444: return "LinksSolidShapesVector_erase"; + case 1445: return "new_LinksSolidShapesVector"; + case 1446: return "LinksSolidShapesVector_push_back"; + case 1447: return "LinksSolidShapesVector_front"; + case 1448: return "LinksSolidShapesVector_back"; + case 1449: return "LinksSolidShapesVector_assign"; + case 1450: return "LinksSolidShapesVector_resize"; + case 1451: return "LinksSolidShapesVector_insert"; + case 1452: return "LinksSolidShapesVector_reserve"; + case 1453: return "LinksSolidShapesVector_capacity"; + case 1454: return "delete_LinksSolidShapesVector"; + case 1455: return "_wrap_ForwardPositionKinematics"; + case 1456: return "_wrap_ForwardVelAccKinematics"; + case 1457: return "_wrap_ForwardPosVelAccKinematics"; + case 1458: return "_wrap_ForwardPosVelKinematics"; + case 1459: return "_wrap_ForwardAccKinematics"; + case 1460: return "_wrap_ForwardBiasAccKinematics"; + case 1461: return "_wrap_ComputeLinearAndAngularMomentum"; + case 1462: return "_wrap_ComputeLinearAndAngularMomentumDerivativeBias"; + case 1463: return "_wrap_RNEADynamicPhase"; + case 1464: return "_wrap_CompositeRigidBodyAlgorithm"; + case 1465: return "new_ArticulatedBodyAlgorithmInternalBuffers"; + case 1466: return "ArticulatedBodyAlgorithmInternalBuffers_resize"; + case 1467: return "ArticulatedBodyAlgorithmInternalBuffers_isConsistent"; + case 1468: return "ArticulatedBodyAlgorithmInternalBuffers_S_get"; + case 1469: return "ArticulatedBodyAlgorithmInternalBuffers_S_set"; + case 1470: return "ArticulatedBodyAlgorithmInternalBuffers_U_get"; + case 1471: return "ArticulatedBodyAlgorithmInternalBuffers_U_set"; + case 1472: return "ArticulatedBodyAlgorithmInternalBuffers_D_get"; + case 1473: return "ArticulatedBodyAlgorithmInternalBuffers_D_set"; + case 1474: return "ArticulatedBodyAlgorithmInternalBuffers_u_get"; + case 1475: return "ArticulatedBodyAlgorithmInternalBuffers_u_set"; + case 1476: return "ArticulatedBodyAlgorithmInternalBuffers_linksVel_get"; + case 1477: return "ArticulatedBodyAlgorithmInternalBuffers_linksVel_set"; + case 1478: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get"; + case 1479: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set"; + case 1480: return "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get"; + case 1481: return "ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set"; + case 1482: return "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get"; + case 1483: return "ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set"; + case 1484: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get"; + case 1485: return "ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set"; + case 1486: return "delete_ArticulatedBodyAlgorithmInternalBuffers"; + case 1487: return "_wrap_ArticulatedBodyAlgorithm"; + case 1488: return "_wrap_InverseDynamicsInertialParametersRegressor"; + case 1489: return "DHLink_A_get"; + case 1490: return "DHLink_A_set"; + case 1491: return "DHLink_D_get"; + case 1492: return "DHLink_D_set"; + case 1493: return "DHLink_Alpha_get"; + case 1494: return "DHLink_Alpha_set"; + case 1495: return "DHLink_Offset_get"; + case 1496: return "DHLink_Offset_set"; + case 1497: return "DHLink_Min_get"; + case 1498: return "DHLink_Min_set"; + case 1499: return "DHLink_Max_get"; + case 1500: return "DHLink_Max_set"; + case 1501: return "new_DHLink"; + case 1502: return "delete_DHLink"; + case 1503: return "DHChain_setNrOfDOFs"; + case 1504: return "DHChain_getNrOfDOFs"; + case 1505: return "DHChain_setH0"; + case 1506: return "DHChain_getH0"; + case 1507: return "DHChain_setHN"; + case 1508: return "DHChain_getHN"; + case 1509: return "DHChain_paren"; + case 1510: return "DHChain_getDOFName"; + case 1511: return "DHChain_setDOFName"; + case 1512: return "DHChain_toModel"; + case 1513: return "DHChain_fromModel"; + case 1514: return "new_DHChain"; + case 1515: return "delete_DHChain"; + case 1516: return "_wrap_TransformFromDHCraig1989"; + case 1517: return "_wrap_TransformFromDH"; + case 1518: return "_wrap_ExtractDHChainFromModel"; + case 1519: return "_wrap_CreateModelFromDHChain"; + case 1520: return "_wrap_dofsListFromURDF"; + case 1521: return "_wrap_dofsListFromURDFString"; + case 1522: return "ModelParserOptions_addSensorFramesAsAdditionalFrames_get"; + case 1523: return "ModelParserOptions_addSensorFramesAsAdditionalFrames_set"; + case 1524: return "ModelParserOptions_originalFilename_get"; + case 1525: return "ModelParserOptions_originalFilename_set"; + case 1526: return "new_ModelParserOptions"; + case 1527: return "delete_ModelParserOptions"; + case 1528: return "new_ModelLoader"; + case 1529: return "delete_ModelLoader"; + case 1530: return "ModelLoader_parsingOptions"; + case 1531: return "ModelLoader_setParsingOptions"; + case 1532: return "ModelLoader_loadModelFromString"; + case 1533: return "ModelLoader_loadModelFromFile"; + case 1534: return "ModelLoader_loadReducedModelFromFullModel"; + case 1535: return "ModelLoader_loadReducedModelFromString"; + case 1536: return "ModelLoader_loadReducedModelFromFile"; + case 1537: return "ModelLoader_model"; + case 1538: return "ModelLoader_sensors"; + case 1539: return "ModelLoader_isValid"; + case 1540: return "ModelExporterOptions_baseLink_get"; + case 1541: return "ModelExporterOptions_baseLink_set"; + case 1542: return "ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_get"; + case 1543: return "ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_set"; + case 1544: return "ModelExporterOptions_robotExportedName_get"; + case 1545: return "ModelExporterOptions_robotExportedName_set"; + case 1546: return "ModelExporterOptions_xmlBlobs_get"; + case 1547: return "ModelExporterOptions_xmlBlobs_set"; + case 1548: return "new_ModelExporterOptions"; + case 1549: return "delete_ModelExporterOptions"; + case 1550: return "new_ModelExporter"; + case 1551: return "delete_ModelExporter"; + case 1552: return "ModelExporter_exportingOptions"; + case 1553: return "ModelExporter_setExportingOptions"; + case 1554: return "ModelExporter_init"; + case 1555: return "ModelExporter_model"; + case 1556: return "ModelExporter_sensors"; + case 1557: return "ModelExporter_isValid"; + case 1558: return "ModelExporter_exportModelToString"; + case 1559: return "ModelExporter_exportModelToFile"; + case 1560: return "new_ModelCalibrationHelper"; + case 1561: return "delete_ModelCalibrationHelper"; + case 1562: return "ModelCalibrationHelper_loadModelFromString"; + case 1563: return "ModelCalibrationHelper_loadModelFromFile"; + case 1564: return "ModelCalibrationHelper_updateModelInertialParametersToString"; + case 1565: return "ModelCalibrationHelper_updateModelInertialParametersToFile"; + case 1566: return "ModelCalibrationHelper_model"; + case 1567: return "ModelCalibrationHelper_sensors"; + case 1568: return "ModelCalibrationHelper_isValid"; + case 1569: return "new_UnknownWrenchContact"; + case 1570: return "UnknownWrenchContact_unknownType_get"; + case 1571: return "UnknownWrenchContact_unknownType_set"; + case 1572: return "UnknownWrenchContact_contactPoint_get"; + case 1573: return "UnknownWrenchContact_contactPoint_set"; + case 1574: return "UnknownWrenchContact_forceDirection_get"; + case 1575: return "UnknownWrenchContact_forceDirection_set"; + case 1576: return "UnknownWrenchContact_knownWrench_get"; + case 1577: return "UnknownWrenchContact_knownWrench_set"; + case 1578: return "UnknownWrenchContact_contactId_get"; + case 1579: return "UnknownWrenchContact_contactId_set"; + case 1580: return "delete_UnknownWrenchContact"; + case 1581: return "new_LinkUnknownWrenchContacts"; + case 1582: return "LinkUnknownWrenchContacts_clear"; + case 1583: return "LinkUnknownWrenchContacts_resize"; + case 1584: return "LinkUnknownWrenchContacts_getNrOfContactsForLink"; + case 1585: return "LinkUnknownWrenchContacts_setNrOfContactsForLink"; + case 1586: return "LinkUnknownWrenchContacts_addNewContactForLink"; + case 1587: return "LinkUnknownWrenchContacts_addNewContactInFrame"; + case 1588: return "LinkUnknownWrenchContacts_addNewUnknownFullWrenchInFrameOrigin"; + case 1589: return "LinkUnknownWrenchContacts_contactWrench"; + case 1590: return "LinkUnknownWrenchContacts_toString"; + case 1591: return "delete_LinkUnknownWrenchContacts"; + case 1592: return "new_estimateExternalWrenchesBuffers"; + case 1593: return "estimateExternalWrenchesBuffers_resize"; + case 1594: return "estimateExternalWrenchesBuffers_getNrOfSubModels"; + case 1595: return "estimateExternalWrenchesBuffers_getNrOfLinks"; + case 1596: return "estimateExternalWrenchesBuffers_isConsistent"; + case 1597: return "estimateExternalWrenchesBuffers_A_get"; + case 1598: return "estimateExternalWrenchesBuffers_A_set"; + case 1599: return "estimateExternalWrenchesBuffers_x_get"; + case 1600: return "estimateExternalWrenchesBuffers_x_set"; + case 1601: return "estimateExternalWrenchesBuffers_b_get"; + case 1602: return "estimateExternalWrenchesBuffers_b_set"; + case 1603: return "estimateExternalWrenchesBuffers_b_contacts_subtree_get"; + case 1604: return "estimateExternalWrenchesBuffers_b_contacts_subtree_set"; + case 1605: return "estimateExternalWrenchesBuffers_subModelBase_H_link_get"; + case 1606: return "estimateExternalWrenchesBuffers_subModelBase_H_link_set"; + case 1607: return "delete_estimateExternalWrenchesBuffers"; + case 1608: return "_wrap_estimateExternalWrenchesWithoutInternalFT"; + case 1609: return "_wrap_estimateExternalWrenches"; + case 1610: return "_wrap_dynamicsEstimationForwardVelAccKinematics"; + case 1611: return "_wrap_dynamicsEstimationForwardVelKinematics"; + case 1612: return "_wrap_computeLinkNetWrenchesWithoutGravity"; + case 1613: return "_wrap_estimateLinkContactWrenchesFromLinkNetExternalWrenches"; + case 1614: return "new_ExtWrenchesAndJointTorquesEstimator"; + case 1615: return "delete_ExtWrenchesAndJointTorquesEstimator"; + case 1616: return "ExtWrenchesAndJointTorquesEstimator_setModel"; + case 1617: return "ExtWrenchesAndJointTorquesEstimator_setModelAndSensors"; + case 1618: return "ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFile"; + case 1619: return "ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFileWithSpecifiedDOFs"; + case 1620: return "ExtWrenchesAndJointTorquesEstimator_model"; + case 1621: return "ExtWrenchesAndJointTorquesEstimator_sensors"; + case 1622: return "ExtWrenchesAndJointTorquesEstimator_submodels"; + case 1623: return "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase"; + case 1624: return "ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase"; + case 1625: return "ExtWrenchesAndJointTorquesEstimator_computeExpectedFTSensorsMeasurements"; + case 1626: return "ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics"; + case 1627: return "ExtWrenchesAndJointTorquesEstimator_estimateExtWrenchesAndJointTorques"; + case 1628: return "ExtWrenchesAndJointTorquesEstimator_checkThatTheModelIsStill"; + case 1629: return "ExtWrenchesAndJointTorquesEstimator_estimateLinkNetWrenchesWithoutGravity"; + case 1630: return "new_SimpleLeggedOdometry"; + case 1631: return "delete_SimpleLeggedOdometry"; + case 1632: return "SimpleLeggedOdometry_setModel"; + case 1633: return "SimpleLeggedOdometry_model"; + case 1634: return "SimpleLeggedOdometry_updateKinematics"; + case 1635: return "SimpleLeggedOdometry_init"; + case 1636: return "SimpleLeggedOdometry_changeFixedFrame"; + case 1637: return "SimpleLeggedOdometry_getCurrentFixedLink"; + case 1638: return "SimpleLeggedOdometry_getWorldLinkTransform"; + case 1639: return "SimpleLeggedOdometry_getWorldFrameTransform"; + case 1640: return "_wrap_isLinkBerdyDynamicVariable"; + case 1641: return "_wrap_isJointBerdyDynamicVariable"; + case 1642: return "_wrap_isDOFBerdyDynamicVariable"; + case 1643: return "new_BerdyOptions"; + case 1644: return "BerdyOptions_berdyVariant_get"; + case 1645: return "BerdyOptions_berdyVariant_set"; + case 1646: return "BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_get"; + case 1647: return "BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_set"; + case 1648: return "BerdyOptions_includeAllJointAccelerationsAsSensors_get"; + case 1649: return "BerdyOptions_includeAllJointAccelerationsAsSensors_set"; + case 1650: return "BerdyOptions_includeAllJointTorquesAsSensors_get"; + case 1651: return "BerdyOptions_includeAllJointTorquesAsSensors_set"; + case 1652: return "BerdyOptions_includeAllNetExternalWrenchesAsSensors_get"; + case 1653: return "BerdyOptions_includeAllNetExternalWrenchesAsSensors_set"; + case 1654: return "BerdyOptions_includeFixedBaseExternalWrench_get"; + case 1655: return "BerdyOptions_includeFixedBaseExternalWrench_set"; + case 1656: return "BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_get"; + case 1657: return "BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_set"; + case 1658: return "BerdyOptions_baseLink_get"; + case 1659: return "BerdyOptions_baseLink_set"; + case 1660: return "BerdyOptions_checkConsistency"; + case 1661: return "delete_BerdyOptions"; + case 1662: return "BerdySensor_type_get"; + case 1663: return "BerdySensor_type_set"; + case 1664: return "BerdySensor_id_get"; + case 1665: return "BerdySensor_id_set"; + case 1666: return "BerdySensor_range_get"; + case 1667: return "BerdySensor_range_set"; + case 1668: return "BerdySensor_eq"; + case 1669: return "BerdySensor_lt"; + case 1670: return "new_BerdySensor"; + case 1671: return "delete_BerdySensor"; + case 1672: return "BerdyDynamicVariable_type_get"; + case 1673: return "BerdyDynamicVariable_type_set"; + case 1674: return "BerdyDynamicVariable_id_get"; + case 1675: return "BerdyDynamicVariable_id_set"; + case 1676: return "BerdyDynamicVariable_range_get"; + case 1677: return "BerdyDynamicVariable_range_set"; + case 1678: return "BerdyDynamicVariable_eq"; + case 1679: return "BerdyDynamicVariable_lt"; + case 1680: return "new_BerdyDynamicVariable"; + case 1681: return "delete_BerdyDynamicVariable"; + case 1682: return "new_BerdyHelper"; + case 1683: return "BerdyHelper_dynamicTraversal"; + case 1684: return "BerdyHelper_model"; + case 1685: return "BerdyHelper_sensors"; + case 1686: return "BerdyHelper_isValid"; + case 1687: return "BerdyHelper_init"; + case 1688: return "BerdyHelper_getOptions"; + case 1689: return "BerdyHelper_getNrOfDynamicVariables"; + case 1690: return "BerdyHelper_getNrOfDynamicEquations"; + case 1691: return "BerdyHelper_getNrOfSensorsMeasurements"; + case 1692: return "BerdyHelper_resizeAndZeroBerdyMatrices"; + case 1693: return "BerdyHelper_getBerdyMatrices"; + case 1694: return "BerdyHelper_getSensorsOrdering"; + case 1695: return "BerdyHelper_getRangeSensorVariable"; + case 1696: return "BerdyHelper_getRangeDOFSensorVariable"; + case 1697: return "BerdyHelper_getRangeJointSensorVariable"; + case 1698: return "BerdyHelper_getRangeLinkSensorVariable"; + case 1699: return "BerdyHelper_getRangeRCMSensorVariable"; + case 1700: return "BerdyHelper_getRangeLinkVariable"; + case 1701: return "BerdyHelper_getRangeJointVariable"; + case 1702: return "BerdyHelper_getRangeDOFVariable"; + case 1703: return "BerdyHelper_getDynamicVariablesOrdering"; + case 1704: return "BerdyHelper_serializeDynamicVariables"; + case 1705: return "BerdyHelper_serializeSensorVariables"; + case 1706: return "BerdyHelper_serializeDynamicVariablesComputedFromFixedBaseRNEA"; + case 1707: return "BerdyHelper_extractJointTorquesFromDynamicVariables"; + case 1708: return "BerdyHelper_extractLinkNetExternalWrenchesFromDynamicVariables"; + case 1709: return "BerdyHelper_updateKinematicsFromFloatingBase"; + case 1710: return "BerdyHelper_updateKinematicsFromFixedBase"; + case 1711: return "BerdyHelper_updateKinematicsFromTraversalFixedBase"; + case 1712: return "BerdyHelper_setNetExternalWrenchMeasurementFrame"; + case 1713: return "BerdyHelper_getNetExternalWrenchMeasurementFrame"; + case 1714: return "delete_BerdyHelper"; + case 1715: return "new_BerdySparseMAPSolver"; + case 1716: return "delete_BerdySparseMAPSolver"; + case 1717: return "BerdySparseMAPSolver_setDynamicsConstraintsPriorCovariance"; + case 1718: return "BerdySparseMAPSolver_setDynamicsRegularizationPriorCovariance"; + case 1719: return "BerdySparseMAPSolver_setDynamicsRegularizationPriorExpectedValue"; + case 1720: return "BerdySparseMAPSolver_setMeasurementsPriorCovariance"; + case 1721: return "BerdySparseMAPSolver_dynamicsConstraintsPriorCovarianceInverse"; + case 1722: return "BerdySparseMAPSolver_dynamicsRegularizationPriorCovarianceInverse"; + case 1723: return "BerdySparseMAPSolver_dynamicsRegularizationPriorExpectedValue"; + case 1724: return "BerdySparseMAPSolver_measurementsPriorCovarianceInverse"; + case 1725: return "BerdySparseMAPSolver_isValid"; + case 1726: return "BerdySparseMAPSolver_initialize"; + case 1727: return "BerdySparseMAPSolver_updateEstimateInformationFixedBase"; + case 1728: return "BerdySparseMAPSolver_updateEstimateInformationFloatingBase"; + case 1729: return "BerdySparseMAPSolver_doEstimate"; + case 1730: return "BerdySparseMAPSolver_getLastEstimate"; + case 1731: return "AttitudeEstimatorState_m_orientation_get"; + case 1732: return "AttitudeEstimatorState_m_orientation_set"; + case 1733: return "AttitudeEstimatorState_m_angular_velocity_get"; + case 1734: return "AttitudeEstimatorState_m_angular_velocity_set"; + case 1735: return "AttitudeEstimatorState_m_gyroscope_bias_get"; + case 1736: return "AttitudeEstimatorState_m_gyroscope_bias_set"; + case 1737: return "new_AttitudeEstimatorState"; + case 1738: return "delete_AttitudeEstimatorState"; + case 1739: return "delete_IAttitudeEstimator"; + case 1740: return "IAttitudeEstimator_updateFilterWithMeasurements"; + case 1741: return "IAttitudeEstimator_propagateStates"; + case 1742: return "IAttitudeEstimator_getOrientationEstimateAsRotationMatrix"; + case 1743: return "IAttitudeEstimator_getOrientationEstimateAsQuaternion"; + case 1744: return "IAttitudeEstimator_getOrientationEstimateAsRPY"; + case 1745: return "IAttitudeEstimator_getInternalStateSize"; + case 1746: return "IAttitudeEstimator_getInternalState"; + case 1747: return "IAttitudeEstimator_getDefaultInternalInitialState"; + case 1748: return "IAttitudeEstimator_setInternalState"; + case 1749: return "IAttitudeEstimator_setInternalStateInitialOrientation"; + case 1750: return "AttitudeMahonyFilterParameters_time_step_in_seconds_get"; + case 1751: return "AttitudeMahonyFilterParameters_time_step_in_seconds_set"; + case 1752: return "AttitudeMahonyFilterParameters_kp_get"; + case 1753: return "AttitudeMahonyFilterParameters_kp_set"; + case 1754: return "AttitudeMahonyFilterParameters_ki_get"; + case 1755: return "AttitudeMahonyFilterParameters_ki_set"; + case 1756: return "AttitudeMahonyFilterParameters_use_magnetometer_measurements_get"; + case 1757: return "AttitudeMahonyFilterParameters_use_magnetometer_measurements_set"; + case 1758: return "AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_get"; + case 1759: return "AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_set"; + case 1760: return "new_AttitudeMahonyFilterParameters"; + case 1761: return "delete_AttitudeMahonyFilterParameters"; + case 1762: return "new_AttitudeMahonyFilter"; + case 1763: return "AttitudeMahonyFilter_useMagnetoMeterMeasurements"; + case 1764: return "AttitudeMahonyFilter_setConfidenceForMagnetometerMeasurements"; + case 1765: return "AttitudeMahonyFilter_setGainkp"; + case 1766: return "AttitudeMahonyFilter_setGainki"; + case 1767: return "AttitudeMahonyFilter_setTimeStepInSeconds"; + case 1768: return "AttitudeMahonyFilter_setGravityDirection"; + case 1769: return "AttitudeMahonyFilter_setParameters"; + case 1770: return "AttitudeMahonyFilter_getParameters"; + case 1771: return "AttitudeMahonyFilter_updateFilterWithMeasurements"; + case 1772: return "AttitudeMahonyFilter_propagateStates"; + case 1773: return "AttitudeMahonyFilter_getOrientationEstimateAsRotationMatrix"; + case 1774: return "AttitudeMahonyFilter_getOrientationEstimateAsQuaternion"; + case 1775: return "AttitudeMahonyFilter_getOrientationEstimateAsRPY"; + case 1776: return "AttitudeMahonyFilter_getInternalStateSize"; + case 1777: return "AttitudeMahonyFilter_getInternalState"; + case 1778: return "AttitudeMahonyFilter_getDefaultInternalInitialState"; + case 1779: return "AttitudeMahonyFilter_setInternalState"; + case 1780: return "AttitudeMahonyFilter_setInternalStateInitialOrientation"; + case 1781: return "delete_AttitudeMahonyFilter"; + case 1782: return "DiscreteExtendedKalmanFilterHelper_ekf_f"; + case 1783: return "DiscreteExtendedKalmanFilterHelper_ekf_h"; + case 1784: return "DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianF"; + case 1785: return "DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianH"; + case 1786: return "DiscreteExtendedKalmanFilterHelper_ekfPredict"; + case 1787: return "DiscreteExtendedKalmanFilterHelper_ekfUpdate"; + case 1788: return "DiscreteExtendedKalmanFilterHelper_ekfInit"; + case 1789: return "DiscreteExtendedKalmanFilterHelper_ekfReset"; + case 1790: return "DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementVector"; + case 1791: return "DiscreteExtendedKalmanFilterHelper_ekfSetInputVector"; + case 1792: return "DiscreteExtendedKalmanFilterHelper_ekfSetInitialState"; + case 1793: return "DiscreteExtendedKalmanFilterHelper_ekfSetStateCovariance"; + case 1794: return "DiscreteExtendedKalmanFilterHelper_ekfSetSystemNoiseCovariance"; + case 1795: return "DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementNoiseCovariance"; + case 1796: return "DiscreteExtendedKalmanFilterHelper_ekfSetStateSize"; + case 1797: return "DiscreteExtendedKalmanFilterHelper_ekfSetInputSize"; + case 1798: return "DiscreteExtendedKalmanFilterHelper_ekfSetOutputSize"; + case 1799: return "DiscreteExtendedKalmanFilterHelper_ekfGetStates"; + case 1800: return "DiscreteExtendedKalmanFilterHelper_ekfGetStateCovariance"; + case 1801: return "delete_DiscreteExtendedKalmanFilterHelper"; + case 1802: return "output_dimensions_with_magnetometer_get"; + case 1803: return "output_dimensions_without_magnetometer_get"; + case 1804: return "input_dimensions_get"; + case 1805: return "AttitudeQuaternionEKFParameters_time_step_in_seconds_get"; + case 1806: return "AttitudeQuaternionEKFParameters_time_step_in_seconds_set"; + case 1807: return "AttitudeQuaternionEKFParameters_bias_correlation_time_factor_get"; + case 1808: return "AttitudeQuaternionEKFParameters_bias_correlation_time_factor_set"; + case 1809: return "AttitudeQuaternionEKFParameters_accelerometer_noise_variance_get"; + case 1810: return "AttitudeQuaternionEKFParameters_accelerometer_noise_variance_set"; + case 1811: return "AttitudeQuaternionEKFParameters_magnetometer_noise_variance_get"; + case 1812: return "AttitudeQuaternionEKFParameters_magnetometer_noise_variance_set"; + case 1813: return "AttitudeQuaternionEKFParameters_gyroscope_noise_variance_get"; + case 1814: return "AttitudeQuaternionEKFParameters_gyroscope_noise_variance_set"; + case 1815: return "AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_get"; + case 1816: return "AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_set"; + case 1817: return "AttitudeQuaternionEKFParameters_initial_orientation_error_variance_get"; + case 1818: return "AttitudeQuaternionEKFParameters_initial_orientation_error_variance_set"; + case 1819: return "AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_get"; + case 1820: return "AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_set"; + case 1821: return "AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_get"; + case 1822: return "AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_set"; + case 1823: return "AttitudeQuaternionEKFParameters_use_magnetometer_measurements_get"; + case 1824: return "AttitudeQuaternionEKFParameters_use_magnetometer_measurements_set"; + case 1825: return "new_AttitudeQuaternionEKFParameters"; + case 1826: return "delete_AttitudeQuaternionEKFParameters"; + case 1827: return "new_AttitudeQuaternionEKF"; + case 1828: return "AttitudeQuaternionEKF_getParameters"; + case 1829: return "AttitudeQuaternionEKF_setParameters"; + case 1830: return "AttitudeQuaternionEKF_setGravityDirection"; + case 1831: return "AttitudeQuaternionEKF_setTimeStepInSeconds"; + case 1832: return "AttitudeQuaternionEKF_setBiasCorrelationTimeFactor"; + case 1833: return "AttitudeQuaternionEKF_useMagnetometerMeasurements"; + case 1834: return "AttitudeQuaternionEKF_setMeasurementNoiseVariance"; + case 1835: return "AttitudeQuaternionEKF_setSystemNoiseVariance"; + case 1836: return "AttitudeQuaternionEKF_setInitialStateCovariance"; + case 1837: return "AttitudeQuaternionEKF_initializeFilter"; + case 1838: return "AttitudeQuaternionEKF_updateFilterWithMeasurements"; + case 1839: return "AttitudeQuaternionEKF_propagateStates"; + case 1840: return "AttitudeQuaternionEKF_getOrientationEstimateAsRotationMatrix"; + case 1841: return "AttitudeQuaternionEKF_getOrientationEstimateAsQuaternion"; + case 1842: return "AttitudeQuaternionEKF_getOrientationEstimateAsRPY"; + case 1843: return "AttitudeQuaternionEKF_getInternalStateSize"; + case 1844: return "AttitudeQuaternionEKF_getInternalState"; + case 1845: return "AttitudeQuaternionEKF_getDefaultInternalInitialState"; + case 1846: return "AttitudeQuaternionEKF_setInternalState"; + case 1847: return "AttitudeQuaternionEKF_setInternalStateInitialOrientation"; + case 1848: return "delete_AttitudeQuaternionEKF"; + case 1849: return "_wrap_estimateInertialParametersFromLinkBoundingBoxesAndTotalMass"; + case 1850: return "_wrap_computeBoundingBoxFromShape"; + case 1851: return "_wrap_computeBoxVertices"; + case 1852: return "new_KinDynComputations"; + case 1853: return "delete_KinDynComputations"; + case 1854: return "KinDynComputations_loadRobotModel"; + case 1855: return "KinDynComputations_isValid"; + case 1856: return "KinDynComputations_setFrameVelocityRepresentation"; + case 1857: return "KinDynComputations_getFrameVelocityRepresentation"; + case 1858: return "KinDynComputations_getNrOfDegreesOfFreedom"; + case 1859: return "KinDynComputations_getDescriptionOfDegreeOfFreedom"; + case 1860: return "KinDynComputations_getDescriptionOfDegreesOfFreedom"; + case 1861: return "KinDynComputations_getNrOfLinks"; + case 1862: return "KinDynComputations_getNrOfFrames"; + case 1863: return "KinDynComputations_getFloatingBase"; + case 1864: return "KinDynComputations_setFloatingBase"; + case 1865: return "KinDynComputations_model"; + case 1866: return "KinDynComputations_getRobotModel"; + case 1867: return "KinDynComputations_getRelativeJacobianSparsityPattern"; + case 1868: return "KinDynComputations_getFrameFreeFloatingJacobianSparsityPattern"; + case 1869: return "KinDynComputations_setJointPos"; + case 1870: return "KinDynComputations_setRobotState"; + case 1871: return "KinDynComputations_getRobotState"; + case 1872: return "KinDynComputations_getWorldBaseTransform"; + case 1873: return "KinDynComputations_getBaseTwist"; + case 1874: return "KinDynComputations_getJointPos"; + case 1875: return "KinDynComputations_getJointVel"; + case 1876: return "KinDynComputations_getModelVel"; + case 1877: return "KinDynComputations_getFrameIndex"; + case 1878: return "KinDynComputations_getFrameName"; + case 1879: return "KinDynComputations_getWorldTransform"; + case 1880: return "KinDynComputations_getWorldTransformsAsHomogeneous"; + case 1881: return "KinDynComputations_getRelativeTransformExplicit"; + case 1882: return "KinDynComputations_getRelativeTransform"; + case 1883: return "KinDynComputations_getFrameVel"; + case 1884: return "KinDynComputations_getFrameAcc"; + case 1885: return "KinDynComputations_getFrameFreeFloatingJacobian"; + case 1886: return "KinDynComputations_getRelativeJacobian"; + case 1887: return "KinDynComputations_getRelativeJacobianExplicit"; + case 1888: return "KinDynComputations_getFrameBiasAcc"; + case 1889: return "KinDynComputations_getCenterOfMassPosition"; + case 1890: return "KinDynComputations_getCenterOfMassVelocity"; + case 1891: return "KinDynComputations_getCenterOfMassJacobian"; + case 1892: return "KinDynComputations_getCenterOfMassBiasAcc"; + case 1893: return "KinDynComputations_getAverageVelocity"; + case 1894: return "KinDynComputations_getAverageVelocityJacobian"; + case 1895: return "KinDynComputations_getCentroidalAverageVelocity"; + case 1896: return "KinDynComputations_getCentroidalAverageVelocityJacobian"; + case 1897: return "KinDynComputations_getLinearAngularMomentum"; + case 1898: return "KinDynComputations_getLinearAngularMomentumJacobian"; + case 1899: return "KinDynComputations_getCentroidalTotalMomentum"; + case 1900: return "KinDynComputations_getCentroidalTotalMomentumJacobian"; + case 1901: return "KinDynComputations_getFreeFloatingMassMatrix"; + case 1902: return "KinDynComputations_inverseDynamics"; + case 1903: return "KinDynComputations_inverseDynamicsWithInternalJointForceTorques"; + case 1904: return "KinDynComputations_generalizedBiasForces"; + case 1905: return "KinDynComputations_generalizedGravityForces"; + case 1906: return "KinDynComputations_generalizedExternalForces"; + case 1907: return "KinDynComputations_inverseDynamicsInertialParametersRegressor"; + case 1908: return "Matrix4x4Vector_pop"; + case 1909: return "Matrix4x4Vector_brace"; + case 1910: return "Matrix4x4Vector_setbrace"; + case 1911: return "Matrix4x4Vector_append"; + case 1912: return "Matrix4x4Vector_empty"; + case 1913: return "Matrix4x4Vector_size"; + case 1914: return "Matrix4x4Vector_swap"; + case 1915: return "Matrix4x4Vector_begin"; + case 1916: return "Matrix4x4Vector_end"; + case 1917: return "Matrix4x4Vector_rbegin"; + case 1918: return "Matrix4x4Vector_rend"; + case 1919: return "Matrix4x4Vector_clear"; + case 1920: return "Matrix4x4Vector_get_allocator"; + case 1921: return "Matrix4x4Vector_pop_back"; + case 1922: return "Matrix4x4Vector_erase"; + case 1923: return "new_Matrix4x4Vector"; + case 1924: return "Matrix4x4Vector_push_back"; + case 1925: return "Matrix4x4Vector_front"; + case 1926: return "Matrix4x4Vector_back"; + case 1927: return "Matrix4x4Vector_assign"; + case 1928: return "Matrix4x4Vector_resize"; + case 1929: return "Matrix4x4Vector_insert"; + case 1930: return "Matrix4x4Vector_reserve"; + case 1931: return "Matrix4x4Vector_capacity"; + case 1932: return "Matrix4x4Vector_toMatlab"; + case 1933: return "delete_Matrix4x4Vector"; + case 1934: return "ICameraAnimator_enableMouseControl"; + case 1935: return "ICameraAnimator_getMoveSpeed"; + case 1936: return "ICameraAnimator_setMoveSpeed"; + case 1937: return "ICameraAnimator_getRotateSpeed"; + case 1938: return "ICameraAnimator_setRotateSpeed"; + case 1939: return "ICameraAnimator_getZoomSpeed"; + case 1940: return "ICameraAnimator_setZoomSpeed"; + case 1941: return "delete_ICameraAnimator"; + case 1942: return "delete_ICamera"; + case 1943: return "ICamera_setPosition"; + case 1944: return "ICamera_setTarget"; + case 1945: return "ICamera_getPosition"; + case 1946: return "ICamera_getTarget"; + case 1947: return "ICamera_setUpVector"; + case 1948: return "ICamera_animator"; + case 1949: return "ColorViz_r_get"; + case 1950: return "ColorViz_r_set"; + case 1951: return "ColorViz_g_get"; + case 1952: return "ColorViz_g_set"; + case 1953: return "ColorViz_b_get"; + case 1954: return "ColorViz_b_set"; + case 1955: return "ColorViz_a_get"; + case 1956: return "ColorViz_a_set"; + case 1957: return "new_ColorViz"; + case 1958: return "delete_ColorViz"; + case 1959: return "PixelViz_width_get"; + case 1960: return "PixelViz_width_set"; + case 1961: return "PixelViz_height_get"; + case 1962: return "PixelViz_height_set"; + case 1963: return "new_PixelViz"; + case 1964: return "delete_PixelViz"; + case 1965: return "delete_ILight"; + case 1966: return "ILight_getName"; + case 1967: return "ILight_setType"; + case 1968: return "ILight_getType"; + case 1969: return "ILight_setPosition"; + case 1970: return "ILight_getPosition"; + case 1971: return "ILight_setDirection"; + case 1972: return "ILight_getDirection"; + case 1973: return "ILight_setAmbientColor"; + case 1974: return "ILight_getAmbientColor"; + case 1975: return "ILight_setSpecularColor"; + case 1976: return "ILight_getSpecularColor"; + case 1977: return "ILight_setDiffuseColor"; + case 1978: return "ILight_getDiffuseColor"; + case 1979: return "delete_IEnvironment"; + case 1980: return "IEnvironment_getElements"; + case 1981: return "IEnvironment_setElementVisibility"; + case 1982: return "IEnvironment_setBackgroundColor"; + case 1983: return "IEnvironment_setFloorGridColor"; + case 1984: return "IEnvironment_setAmbientLight"; + case 1985: return "IEnvironment_getLights"; + case 1986: return "IEnvironment_addLight"; + case 1987: return "IEnvironment_lightViz"; + case 1988: return "IEnvironment_removeLight"; + case 1989: return "delete_IJetsVisualization"; + case 1990: return "IJetsVisualization_setJetsFrames"; + case 1991: return "IJetsVisualization_getNrOfJets"; + case 1992: return "IJetsVisualization_getJetDirection"; + case 1993: return "IJetsVisualization_setJetDirection"; + case 1994: return "IJetsVisualization_setJetColor"; + case 1995: return "IJetsVisualization_setJetsDimensions"; + case 1996: return "IJetsVisualization_setJetsIntensity"; + case 1997: return "delete_ILabel"; + case 1998: return "ILabel_setText"; + case 1999: return "ILabel_getText"; + case 2000: return "ILabel_setSize"; + case 2001: return "ILabel_width"; + case 2002: return "ILabel_height"; + case 2003: return "ILabel_setPosition"; + case 2004: return "ILabel_getPosition"; + case 2005: return "ILabel_setColor"; + case 2006: return "ILabel_setVisible"; + case 2007: return "delete_IVectorsVisualization"; + case 2008: return "IVectorsVisualization_addVector"; + case 2009: return "IVectorsVisualization_getNrOfVectors"; + case 2010: return "IVectorsVisualization_getVector"; + case 2011: return "IVectorsVisualization_updateVector"; + case 2012: return "IVectorsVisualization_setVectorColor"; + case 2013: return "IVectorsVisualization_setVectorsDefaultColor"; + case 2014: return "IVectorsVisualization_setVectorsColor"; + case 2015: return "IVectorsVisualization_setVectorsAspect"; + case 2016: return "IVectorsVisualization_setVisible"; + case 2017: return "IVectorsVisualization_getVectorLabel"; + case 2018: return "delete_IFrameVisualization"; + case 2019: return "IFrameVisualization_addFrame"; + case 2020: return "IFrameVisualization_setVisible"; + case 2021: return "IFrameVisualization_getNrOfFrames"; + case 2022: return "IFrameVisualization_getFrameTransform"; + case 2023: return "IFrameVisualization_updateFrame"; + case 2024: return "IFrameVisualization_getFrameLabel"; + case 2025: return "delete_IModelVisualization"; + case 2026: return "IModelVisualization_setPositions"; + case 2027: return "IModelVisualization_setLinkPositions"; + case 2028: return "IModelVisualization_model"; + case 2029: return "IModelVisualization_getInstanceName"; + case 2030: return "IModelVisualization_setModelVisibility"; + case 2031: return "IModelVisualization_setModelColor"; + case 2032: return "IModelVisualization_resetModelColor"; + case 2033: return "IModelVisualization_setLinkColor"; + case 2034: return "IModelVisualization_resetLinkColor"; + case 2035: return "IModelVisualization_getLinkNames"; + case 2036: return "IModelVisualization_setLinkVisibility"; + case 2037: return "IModelVisualization_getFeatures"; + case 2038: return "IModelVisualization_setFeatureVisibility"; + case 2039: return "IModelVisualization_jets"; + case 2040: return "IModelVisualization_getWorldLinkTransform"; + case 2041: return "IModelVisualization_getWorldFrameTransform"; + case 2042: return "IModelVisualization_label"; + case 2043: return "delete_ITexture"; + case 2044: return "ITexture_environment"; + case 2045: return "ITexture_getPixelColor"; + case 2046: return "ITexture_getPixels"; + case 2047: return "ITexture_drawToFile"; + case 2048: return "ITexture_enableDraw"; + case 2049: return "ITexture_width"; + case 2050: return "ITexture_height"; + case 2051: return "ITexture_setSubDrawArea"; + case 2052: return "VisualizerOptions_verbose_get"; + case 2053: return "VisualizerOptions_verbose_set"; + case 2054: return "VisualizerOptions_winWidth_get"; + case 2055: return "VisualizerOptions_winWidth_set"; + case 2056: return "VisualizerOptions_winHeight_get"; + case 2057: return "VisualizerOptions_winHeight_set"; + case 2058: return "VisualizerOptions_rootFrameArrowsDimension_get"; + case 2059: return "VisualizerOptions_rootFrameArrowsDimension_set"; + case 2060: return "new_VisualizerOptions"; + case 2061: return "delete_VisualizerOptions"; + case 2062: return "delete_ITexturesHandler"; + case 2063: return "ITexturesHandler_add"; + case 2064: return "ITexturesHandler_get"; + case 2065: return "new_Visualizer"; + case 2066: return "delete_Visualizer"; + case 2067: return "Visualizer_init"; + case 2068: return "Visualizer_getNrOfVisualizedModels"; + case 2069: return "Visualizer_getModelInstanceName"; + case 2070: return "Visualizer_getModelInstanceIndex"; + case 2071: return "Visualizer_addModel"; + case 2072: return "Visualizer_modelViz"; + case 2073: return "Visualizer_camera"; + case 2074: return "Visualizer_enviroment"; + case 2075: return "Visualizer_environment"; + case 2076: return "Visualizer_vectors"; + case 2077: return "Visualizer_frames"; + case 2078: return "Visualizer_textures"; + case 2079: return "Visualizer_getLabel"; + case 2080: return "Visualizer_width"; + case 2081: return "Visualizer_height"; + case 2082: return "Visualizer_run"; + case 2083: return "Visualizer_draw"; + case 2084: return "Visualizer_subDraw"; + case 2085: return "Visualizer_drawToFile"; + case 2086: return "Visualizer_close"; + case 2087: return "Visualizer_isWindowActive"; + case 2088: return "Visualizer_setColorPalette"; + case 2089: return "Polygon_m_vertices_get"; + case 2090: return "Polygon_m_vertices_set"; + case 2091: return "new_Polygon"; + case 2092: return "Polygon_setNrOfVertices"; + case 2093: return "Polygon_getNrOfVertices"; + case 2094: return "Polygon_isValid"; + case 2095: return "Polygon_applyTransform"; + case 2096: return "Polygon_paren"; + case 2097: return "Polygon_XYRectangleFromOffsets"; + case 2098: return "delete_Polygon"; + case 2099: return "Polygon2D_m_vertices_get"; + case 2100: return "Polygon2D_m_vertices_set"; + case 2101: return "new_Polygon2D"; + case 2102: return "Polygon2D_setNrOfVertices"; + case 2103: return "Polygon2D_getNrOfVertices"; + case 2104: return "Polygon2D_isValid"; + case 2105: return "Polygon2D_paren"; + case 2106: return "delete_Polygon2D"; + case 2107: return "ConvexHullProjectionConstraint_setActive"; + case 2108: return "ConvexHullProjectionConstraint_isActive"; + case 2109: return "ConvexHullProjectionConstraint_getNrOfConstraints"; + case 2110: return "ConvexHullProjectionConstraint_projectedConvexHull_get"; + case 2111: return "ConvexHullProjectionConstraint_projectedConvexHull_set"; + case 2112: return "ConvexHullProjectionConstraint_A_get"; + case 2113: return "ConvexHullProjectionConstraint_A_set"; + case 2114: return "ConvexHullProjectionConstraint_b_get"; + case 2115: return "ConvexHullProjectionConstraint_b_set"; + case 2116: return "ConvexHullProjectionConstraint_P_get"; + case 2117: return "ConvexHullProjectionConstraint_P_set"; + case 2118: return "ConvexHullProjectionConstraint_Pdirection_get"; + case 2119: return "ConvexHullProjectionConstraint_Pdirection_set"; + case 2120: return "ConvexHullProjectionConstraint_AtimesP_get"; + case 2121: return "ConvexHullProjectionConstraint_AtimesP_set"; + case 2122: return "ConvexHullProjectionConstraint_o_get"; + case 2123: return "ConvexHullProjectionConstraint_o_set"; + case 2124: return "ConvexHullProjectionConstraint_buildConvexHull"; + case 2125: return "ConvexHullProjectionConstraint_supportFrameIndices_get"; + case 2126: return "ConvexHullProjectionConstraint_supportFrameIndices_set"; + case 2127: return "ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_get"; + case 2128: return "ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_set"; + case 2129: return "ConvexHullProjectionConstraint_project"; + case 2130: return "ConvexHullProjectionConstraint_computeMargin"; + case 2131: return "ConvexHullProjectionConstraint_setProjectionAlongDirection"; + case 2132: return "ConvexHullProjectionConstraint_projectAlongDirection"; + case 2133: return "new_ConvexHullProjectionConstraint"; + case 2134: return "delete_ConvexHullProjectionConstraint"; + case 2135: return "_wrap_sizeOfRotationParametrization"; + case 2136: return "new_InverseKinematics"; + case 2137: return "delete_InverseKinematics"; + case 2138: return "InverseKinematics_loadModelFromFile"; + case 2139: return "InverseKinematics_setModel"; + case 2140: return "InverseKinematics_setJointLimits"; + case 2141: return "InverseKinematics_getJointLimits"; + case 2142: return "InverseKinematics_clearProblem"; + case 2143: return "InverseKinematics_setFloatingBaseOnFrameNamed"; + case 2144: return "InverseKinematics_setCurrentRobotConfiguration"; + case 2145: return "InverseKinematics_setJointConfiguration"; + case 2146: return "InverseKinematics_setRotationParametrization"; + case 2147: return "InverseKinematics_rotationParametrization"; + case 2148: return "InverseKinematics_setMaxIterations"; + case 2149: return "InverseKinematics_maxIterations"; + case 2150: return "InverseKinematics_setMaxCPUTime"; + case 2151: return "InverseKinematics_maxCPUTime"; + case 2152: return "InverseKinematics_setCostTolerance"; + case 2153: return "InverseKinematics_costTolerance"; + case 2154: return "InverseKinematics_setConstraintsTolerance"; + case 2155: return "InverseKinematics_constraintsTolerance"; + case 2156: return "InverseKinematics_setVerbosity"; + case 2157: return "InverseKinematics_linearSolverName"; + case 2158: return "InverseKinematics_setLinearSolverName"; + case 2159: return "InverseKinematics_addFrameConstraint"; + case 2160: return "InverseKinematics_addFramePositionConstraint"; + case 2161: return "InverseKinematics_addFrameRotationConstraint"; + case 2162: return "InverseKinematics_activateFrameConstraint"; + case 2163: return "InverseKinematics_deactivateFrameConstraint"; + case 2164: return "InverseKinematics_isFrameConstraintActive"; + case 2165: return "InverseKinematics_addCenterOfMassProjectionConstraint"; + case 2166: return "InverseKinematics_getCenterOfMassProjectionMargin"; + case 2167: return "InverseKinematics_getCenterOfMassProjectConstraintConvexHull"; + case 2168: return "InverseKinematics_addTarget"; + case 2169: return "InverseKinematics_addPositionTarget"; + case 2170: return "InverseKinematics_addRotationTarget"; + case 2171: return "InverseKinematics_updateTarget"; + case 2172: return "InverseKinematics_updatePositionTarget"; + case 2173: return "InverseKinematics_updateRotationTarget"; + case 2174: return "InverseKinematics_setDefaultTargetResolutionMode"; + case 2175: return "InverseKinematics_defaultTargetResolutionMode"; + case 2176: return "InverseKinematics_setTargetResolutionMode"; + case 2177: return "InverseKinematics_targetResolutionMode"; + case 2178: return "InverseKinematics_setDesiredFullJointsConfiguration"; + case 2179: return "InverseKinematics_setDesiredReducedJointConfiguration"; + case 2180: return "InverseKinematics_setFullJointsInitialCondition"; + case 2181: return "InverseKinematics_setReducedInitialCondition"; + case 2182: return "InverseKinematics_solve"; + case 2183: return "InverseKinematics_getFullJointsSolution"; + case 2184: return "InverseKinematics_getReducedSolution"; + case 2185: return "InverseKinematics_getPoseForFrame"; + case 2186: return "InverseKinematics_fullModel"; + case 2187: return "InverseKinematics_reducedModel"; + case 2188: return "InverseKinematics_setCOMTarget"; + case 2189: return "InverseKinematics_setCOMAsConstraint"; + case 2190: return "InverseKinematics_setCOMAsConstraintTolerance"; + case 2191: return "InverseKinematics_isCOMAConstraint"; + case 2192: return "InverseKinematics_isCOMTargetActive"; + case 2193: return "InverseKinematics_deactivateCOMTarget"; + case 2194: return "InverseKinematics_setCOMConstraintProjectionDirection"; default: return 0; } } @@ -112965,2047 +117401,2130 @@ void mexFunction(int resc, mxArray *resv[], int argc, const mxArray *argv[]) { case 68: flag=_wrap_IntVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; case 69: flag=_wrap_IntVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; case 70: flag=_wrap_delete_IntVector(resc,resv,argc,(mxArray**)(argv)); break; - case 71: flag=_wrap_BerdySensors_pop(resc,resv,argc,(mxArray**)(argv)); break; - case 72: flag=_wrap_BerdySensors_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 73: flag=_wrap_BerdySensors_setbrace(resc,resv,argc,(mxArray**)(argv)); break; - case 74: flag=_wrap_BerdySensors_append(resc,resv,argc,(mxArray**)(argv)); break; - case 75: flag=_wrap_BerdySensors_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 76: flag=_wrap_BerdySensors_size(resc,resv,argc,(mxArray**)(argv)); break; - case 77: flag=_wrap_BerdySensors_swap(resc,resv,argc,(mxArray**)(argv)); break; - case 78: flag=_wrap_BerdySensors_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 79: flag=_wrap_BerdySensors_end(resc,resv,argc,(mxArray**)(argv)); break; - case 80: flag=_wrap_BerdySensors_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 81: flag=_wrap_BerdySensors_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 82: flag=_wrap_BerdySensors_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 83: flag=_wrap_BerdySensors_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; - case 84: flag=_wrap_BerdySensors_pop_back(resc,resv,argc,(mxArray**)(argv)); break; - case 85: flag=_wrap_BerdySensors_erase(resc,resv,argc,(mxArray**)(argv)); break; - case 86: flag=_wrap_new_BerdySensors(resc,resv,argc,(mxArray**)(argv)); break; - case 87: flag=_wrap_BerdySensors_push_back(resc,resv,argc,(mxArray**)(argv)); break; - case 88: flag=_wrap_BerdySensors_front(resc,resv,argc,(mxArray**)(argv)); break; - case 89: flag=_wrap_BerdySensors_back(resc,resv,argc,(mxArray**)(argv)); break; - case 90: flag=_wrap_BerdySensors_assign(resc,resv,argc,(mxArray**)(argv)); break; - case 91: flag=_wrap_BerdySensors_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 92: flag=_wrap_BerdySensors_insert(resc,resv,argc,(mxArray**)(argv)); break; - case 93: flag=_wrap_BerdySensors_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 94: flag=_wrap_BerdySensors_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 95: flag=_wrap_delete_BerdySensors(resc,resv,argc,(mxArray**)(argv)); break; - case 96: flag=_wrap_BerdyDynamicVariables_pop(resc,resv,argc,(mxArray**)(argv)); break; - case 97: flag=_wrap_BerdyDynamicVariables_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 98: flag=_wrap_BerdyDynamicVariables_setbrace(resc,resv,argc,(mxArray**)(argv)); break; - case 99: flag=_wrap_BerdyDynamicVariables_append(resc,resv,argc,(mxArray**)(argv)); break; - case 100: flag=_wrap_BerdyDynamicVariables_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 101: flag=_wrap_BerdyDynamicVariables_size(resc,resv,argc,(mxArray**)(argv)); break; - case 102: flag=_wrap_BerdyDynamicVariables_swap(resc,resv,argc,(mxArray**)(argv)); break; - case 103: flag=_wrap_BerdyDynamicVariables_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 104: flag=_wrap_BerdyDynamicVariables_end(resc,resv,argc,(mxArray**)(argv)); break; - case 105: flag=_wrap_BerdyDynamicVariables_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 106: flag=_wrap_BerdyDynamicVariables_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 107: flag=_wrap_BerdyDynamicVariables_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 108: flag=_wrap_BerdyDynamicVariables_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; - case 109: flag=_wrap_BerdyDynamicVariables_pop_back(resc,resv,argc,(mxArray**)(argv)); break; - case 110: flag=_wrap_BerdyDynamicVariables_erase(resc,resv,argc,(mxArray**)(argv)); break; - case 111: flag=_wrap_new_BerdyDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 112: flag=_wrap_BerdyDynamicVariables_push_back(resc,resv,argc,(mxArray**)(argv)); break; - case 113: flag=_wrap_BerdyDynamicVariables_front(resc,resv,argc,(mxArray**)(argv)); break; - case 114: flag=_wrap_BerdyDynamicVariables_back(resc,resv,argc,(mxArray**)(argv)); break; - case 115: flag=_wrap_BerdyDynamicVariables_assign(resc,resv,argc,(mxArray**)(argv)); break; - case 116: flag=_wrap_BerdyDynamicVariables_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 117: flag=_wrap_BerdyDynamicVariables_insert(resc,resv,argc,(mxArray**)(argv)); break; - case 118: flag=_wrap_BerdyDynamicVariables_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 119: flag=_wrap_BerdyDynamicVariables_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 120: flag=_wrap_delete_BerdyDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 121: flag=_wrap_reportInfo(resc,resv,argc,(mxArray**)(argv)); break; - case 122: flag=_wrap_reportDebug(resc,resv,argc,(mxArray**)(argv)); break; - case 123: flag=_wrap_IndexRange_offset_get(resc,resv,argc,(mxArray**)(argv)); break; - case 124: flag=_wrap_IndexRange_offset_set(resc,resv,argc,(mxArray**)(argv)); break; - case 125: flag=_wrap_IndexRange_size_get(resc,resv,argc,(mxArray**)(argv)); break; - case 126: flag=_wrap_IndexRange_size_set(resc,resv,argc,(mxArray**)(argv)); break; - case 127: flag=_wrap_IndexRange_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 128: flag=_wrap_IndexRange_InvalidRange(resc,resv,argc,(mxArray**)(argv)); break; - case 129: flag=_wrap_new_IndexRange(resc,resv,argc,(mxArray**)(argv)); break; - case 130: flag=_wrap_delete_IndexRange(resc,resv,argc,(mxArray**)(argv)); break; - case 131: flag=_wrap_checkDoublesAreEqual(resc,resv,argc,(mxArray**)(argv)); break; - case 132: flag=_wrap_new_MatrixDynSize(resc,resv,argc,(mxArray**)(argv)); break; - case 133: flag=_wrap_delete_MatrixDynSize(resc,resv,argc,(mxArray**)(argv)); break; - case 134: flag=_wrap_MatrixDynSize_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 135: flag=_wrap_MatrixDynSize_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 136: flag=_wrap_MatrixDynSize_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 137: flag=_wrap_MatrixDynSize_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 138: flag=_wrap_MatrixDynSize_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 139: flag=_wrap_MatrixDynSize_data(resc,resv,argc,(mxArray**)(argv)); break; - case 140: flag=_wrap_MatrixDynSize_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 141: flag=_wrap_MatrixDynSize_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 142: flag=_wrap_MatrixDynSize_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 143: flag=_wrap_MatrixDynSize_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 144: flag=_wrap_MatrixDynSize_shrink_to_fit(resc,resv,argc,(mxArray**)(argv)); break; - case 145: flag=_wrap_MatrixDynSize_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 146: flag=_wrap_MatrixDynSize_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 147: flag=_wrap_MatrixDynSize_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 148: flag=_wrap_MatrixDynSize_display(resc,resv,argc,(mxArray**)(argv)); break; - case 149: flag=_wrap_MatrixDynSize_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 150: flag=_wrap_MatrixDynSize_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 151: flag=_wrap_new_SparseMatrixRowMajor(resc,resv,argc,(mxArray**)(argv)); break; - case 152: flag=_wrap_delete_SparseMatrixRowMajor(resc,resv,argc,(mxArray**)(argv)); break; - case 153: flag=_wrap_SparseMatrixRowMajor_numberOfNonZeros(resc,resv,argc,(mxArray**)(argv)); break; - case 154: flag=_wrap_SparseMatrixRowMajor_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 155: flag=_wrap_SparseMatrixRowMajor_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 156: flag=_wrap_SparseMatrixRowMajor_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 157: flag=_wrap_SparseMatrixRowMajor_setFromConstTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 158: flag=_wrap_SparseMatrixRowMajor_setFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 159: flag=_wrap_SparseMatrixRowMajor_sparseMatrixFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 160: flag=_wrap_SparseMatrixRowMajor_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 161: flag=_wrap_SparseMatrixRowMajor_getValue(resc,resv,argc,(mxArray**)(argv)); break; - case 162: flag=_wrap_SparseMatrixRowMajor_setValue(resc,resv,argc,(mxArray**)(argv)); break; - case 163: flag=_wrap_SparseMatrixRowMajor_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 164: flag=_wrap_SparseMatrixRowMajor_columns(resc,resv,argc,(mxArray**)(argv)); break; - case 165: flag=_wrap_SparseMatrixRowMajor_description(resc,resv,argc,(mxArray**)(argv)); break; - case 166: flag=_wrap_SparseMatrixRowMajor_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 167: flag=_wrap_SparseMatrixRowMajor_toMatlabDense(resc,resv,argc,(mxArray**)(argv)); break; - case 168: flag=_wrap_SparseMatrixRowMajor_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 169: flag=_wrap_new_SparseMatrixColMajor(resc,resv,argc,(mxArray**)(argv)); break; - case 170: flag=_wrap_delete_SparseMatrixColMajor(resc,resv,argc,(mxArray**)(argv)); break; - case 171: flag=_wrap_SparseMatrixColMajor_numberOfNonZeros(resc,resv,argc,(mxArray**)(argv)); break; - case 172: flag=_wrap_SparseMatrixColMajor_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 173: flag=_wrap_SparseMatrixColMajor_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 174: flag=_wrap_SparseMatrixColMajor_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 175: flag=_wrap_SparseMatrixColMajor_setFromConstTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 176: flag=_wrap_SparseMatrixColMajor_setFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 177: flag=_wrap_SparseMatrixColMajor_sparseMatrixFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; - case 178: flag=_wrap_SparseMatrixColMajor_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 179: flag=_wrap_SparseMatrixColMajor_getValue(resc,resv,argc,(mxArray**)(argv)); break; - case 180: flag=_wrap_SparseMatrixColMajor_setValue(resc,resv,argc,(mxArray**)(argv)); break; - case 181: flag=_wrap_SparseMatrixColMajor_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 182: flag=_wrap_SparseMatrixColMajor_columns(resc,resv,argc,(mxArray**)(argv)); break; - case 183: flag=_wrap_SparseMatrixColMajor_description(resc,resv,argc,(mxArray**)(argv)); break; - case 184: flag=_wrap_SparseMatrixColMajor_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 185: flag=_wrap_SparseMatrixColMajor_toMatlabDense(resc,resv,argc,(mxArray**)(argv)); break; - case 186: flag=_wrap_SparseMatrixColMajor_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 187: flag=_wrap_new_VectorDynSize(resc,resv,argc,(mxArray**)(argv)); break; - case 188: flag=_wrap_delete_VectorDynSize(resc,resv,argc,(mxArray**)(argv)); break; - case 189: flag=_wrap_VectorDynSize_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 190: flag=_wrap_VectorDynSize_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 191: flag=_wrap_VectorDynSize_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 192: flag=_wrap_VectorDynSize_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 193: flag=_wrap_VectorDynSize_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 194: flag=_wrap_VectorDynSize_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 195: flag=_wrap_VectorDynSize_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 196: flag=_wrap_VectorDynSize_end(resc,resv,argc,(mxArray**)(argv)); break; - case 197: flag=_wrap_VectorDynSize_size(resc,resv,argc,(mxArray**)(argv)); break; - case 198: flag=_wrap_VectorDynSize_data(resc,resv,argc,(mxArray**)(argv)); break; - case 199: flag=_wrap_VectorDynSize_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 200: flag=_wrap_VectorDynSize_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 201: flag=_wrap_VectorDynSize_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 202: flag=_wrap_VectorDynSize_shrink_to_fit(resc,resv,argc,(mxArray**)(argv)); break; - case 203: flag=_wrap_VectorDynSize_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 204: flag=_wrap_VectorDynSize_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 205: flag=_wrap_VectorDynSize_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 206: flag=_wrap_VectorDynSize_display(resc,resv,argc,(mxArray**)(argv)); break; - case 207: flag=_wrap_VectorDynSize_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 208: flag=_wrap_VectorDynSize_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 209: flag=_wrap_new_Matrix1x6(resc,resv,argc,(mxArray**)(argv)); break; - case 210: flag=_wrap_Matrix1x6_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 211: flag=_wrap_Matrix1x6_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 212: flag=_wrap_Matrix1x6_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 213: flag=_wrap_Matrix1x6_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 214: flag=_wrap_Matrix1x6_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 215: flag=_wrap_Matrix1x6_data(resc,resv,argc,(mxArray**)(argv)); break; - case 216: flag=_wrap_Matrix1x6_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 217: flag=_wrap_Matrix1x6_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 218: flag=_wrap_Matrix1x6_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 219: flag=_wrap_Matrix1x6_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 220: flag=_wrap_Matrix1x6_display(resc,resv,argc,(mxArray**)(argv)); break; - case 221: flag=_wrap_Matrix1x6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 222: flag=_wrap_Matrix1x6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 223: flag=_wrap_delete_Matrix1x6(resc,resv,argc,(mxArray**)(argv)); break; - case 224: flag=_wrap_new_Matrix2x3(resc,resv,argc,(mxArray**)(argv)); break; - case 225: flag=_wrap_Matrix2x3_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 226: flag=_wrap_Matrix2x3_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 227: flag=_wrap_Matrix2x3_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 228: flag=_wrap_Matrix2x3_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 229: flag=_wrap_Matrix2x3_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 230: flag=_wrap_Matrix2x3_data(resc,resv,argc,(mxArray**)(argv)); break; - case 231: flag=_wrap_Matrix2x3_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 232: flag=_wrap_Matrix2x3_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 233: flag=_wrap_Matrix2x3_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 234: flag=_wrap_Matrix2x3_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 235: flag=_wrap_Matrix2x3_display(resc,resv,argc,(mxArray**)(argv)); break; - case 236: flag=_wrap_Matrix2x3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 237: flag=_wrap_Matrix2x3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 238: flag=_wrap_delete_Matrix2x3(resc,resv,argc,(mxArray**)(argv)); break; - case 239: flag=_wrap_new_Matrix3x3(resc,resv,argc,(mxArray**)(argv)); break; - case 240: flag=_wrap_Matrix3x3_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 241: flag=_wrap_Matrix3x3_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 242: flag=_wrap_Matrix3x3_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 243: flag=_wrap_Matrix3x3_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 244: flag=_wrap_Matrix3x3_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 245: flag=_wrap_Matrix3x3_data(resc,resv,argc,(mxArray**)(argv)); break; - case 246: flag=_wrap_Matrix3x3_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 247: flag=_wrap_Matrix3x3_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 248: flag=_wrap_Matrix3x3_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 249: flag=_wrap_Matrix3x3_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 250: flag=_wrap_Matrix3x3_display(resc,resv,argc,(mxArray**)(argv)); break; - case 251: flag=_wrap_Matrix3x3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 252: flag=_wrap_Matrix3x3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 253: flag=_wrap_delete_Matrix3x3(resc,resv,argc,(mxArray**)(argv)); break; - case 254: flag=_wrap_new_Matrix4x4(resc,resv,argc,(mxArray**)(argv)); break; - case 255: flag=_wrap_Matrix4x4_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 256: flag=_wrap_Matrix4x4_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 257: flag=_wrap_Matrix4x4_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 258: flag=_wrap_Matrix4x4_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 259: flag=_wrap_Matrix4x4_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 260: flag=_wrap_Matrix4x4_data(resc,resv,argc,(mxArray**)(argv)); break; - case 261: flag=_wrap_Matrix4x4_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 262: flag=_wrap_Matrix4x4_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 263: flag=_wrap_Matrix4x4_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 264: flag=_wrap_Matrix4x4_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 265: flag=_wrap_Matrix4x4_display(resc,resv,argc,(mxArray**)(argv)); break; - case 266: flag=_wrap_Matrix4x4_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 267: flag=_wrap_Matrix4x4_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 268: flag=_wrap_delete_Matrix4x4(resc,resv,argc,(mxArray**)(argv)); break; - case 269: flag=_wrap_new_Matrix6x6(resc,resv,argc,(mxArray**)(argv)); break; - case 270: flag=_wrap_Matrix6x6_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 271: flag=_wrap_Matrix6x6_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 272: flag=_wrap_Matrix6x6_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 273: flag=_wrap_Matrix6x6_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 274: flag=_wrap_Matrix6x6_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 275: flag=_wrap_Matrix6x6_data(resc,resv,argc,(mxArray**)(argv)); break; - case 276: flag=_wrap_Matrix6x6_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 277: flag=_wrap_Matrix6x6_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 278: flag=_wrap_Matrix6x6_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 279: flag=_wrap_Matrix6x6_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 280: flag=_wrap_Matrix6x6_display(resc,resv,argc,(mxArray**)(argv)); break; - case 281: flag=_wrap_Matrix6x6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 282: flag=_wrap_Matrix6x6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 283: flag=_wrap_delete_Matrix6x6(resc,resv,argc,(mxArray**)(argv)); break; - case 284: flag=_wrap_new_Matrix6x10(resc,resv,argc,(mxArray**)(argv)); break; - case 285: flag=_wrap_Matrix6x10_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 286: flag=_wrap_Matrix6x10_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 287: flag=_wrap_Matrix6x10_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 288: flag=_wrap_Matrix6x10_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 289: flag=_wrap_Matrix6x10_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 290: flag=_wrap_Matrix6x10_data(resc,resv,argc,(mxArray**)(argv)); break; - case 291: flag=_wrap_Matrix6x10_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 292: flag=_wrap_Matrix6x10_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 293: flag=_wrap_Matrix6x10_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 294: flag=_wrap_Matrix6x10_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 295: flag=_wrap_Matrix6x10_display(resc,resv,argc,(mxArray**)(argv)); break; - case 296: flag=_wrap_Matrix6x10_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 297: flag=_wrap_Matrix6x10_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 298: flag=_wrap_delete_Matrix6x10(resc,resv,argc,(mxArray**)(argv)); break; - case 299: flag=_wrap_new_Matrix10x16(resc,resv,argc,(mxArray**)(argv)); break; - case 300: flag=_wrap_Matrix10x16_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 301: flag=_wrap_Matrix10x16_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 302: flag=_wrap_Matrix10x16_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 303: flag=_wrap_Matrix10x16_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 304: flag=_wrap_Matrix10x16_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 305: flag=_wrap_Matrix10x16_data(resc,resv,argc,(mxArray**)(argv)); break; - case 306: flag=_wrap_Matrix10x16_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 307: flag=_wrap_Matrix10x16_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 308: flag=_wrap_Matrix10x16_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 309: flag=_wrap_Matrix10x16_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 310: flag=_wrap_Matrix10x16_display(resc,resv,argc,(mxArray**)(argv)); break; - case 311: flag=_wrap_Matrix10x16_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 312: flag=_wrap_Matrix10x16_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 313: flag=_wrap_delete_Matrix10x16(resc,resv,argc,(mxArray**)(argv)); break; - case 314: flag=_wrap_new_Vector3(resc,resv,argc,(mxArray**)(argv)); break; - case 315: flag=_wrap_Vector3_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 316: flag=_wrap_Vector3_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 317: flag=_wrap_Vector3_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 318: flag=_wrap_Vector3_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 319: flag=_wrap_Vector3_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 320: flag=_wrap_Vector3_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 321: flag=_wrap_Vector3_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 322: flag=_wrap_Vector3_end(resc,resv,argc,(mxArray**)(argv)); break; - case 323: flag=_wrap_Vector3_size(resc,resv,argc,(mxArray**)(argv)); break; - case 324: flag=_wrap_Vector3_data(resc,resv,argc,(mxArray**)(argv)); break; - case 325: flag=_wrap_Vector3_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 326: flag=_wrap_Vector3_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 327: flag=_wrap_Vector3_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 328: flag=_wrap_Vector3_display(resc,resv,argc,(mxArray**)(argv)); break; - case 329: flag=_wrap_Vector3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 330: flag=_wrap_Vector3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 331: flag=_wrap_delete_Vector3(resc,resv,argc,(mxArray**)(argv)); break; - case 332: flag=_wrap_new_Vector4(resc,resv,argc,(mxArray**)(argv)); break; - case 333: flag=_wrap_Vector4_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 334: flag=_wrap_Vector4_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 335: flag=_wrap_Vector4_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 336: flag=_wrap_Vector4_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 337: flag=_wrap_Vector4_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 338: flag=_wrap_Vector4_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 339: flag=_wrap_Vector4_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 340: flag=_wrap_Vector4_end(resc,resv,argc,(mxArray**)(argv)); break; - case 341: flag=_wrap_Vector4_size(resc,resv,argc,(mxArray**)(argv)); break; - case 342: flag=_wrap_Vector4_data(resc,resv,argc,(mxArray**)(argv)); break; - case 343: flag=_wrap_Vector4_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 344: flag=_wrap_Vector4_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 345: flag=_wrap_Vector4_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 346: flag=_wrap_Vector4_display(resc,resv,argc,(mxArray**)(argv)); break; - case 347: flag=_wrap_Vector4_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 348: flag=_wrap_Vector4_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 349: flag=_wrap_delete_Vector4(resc,resv,argc,(mxArray**)(argv)); break; - case 350: flag=_wrap_new_Vector6(resc,resv,argc,(mxArray**)(argv)); break; - case 351: flag=_wrap_Vector6_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 352: flag=_wrap_Vector6_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 353: flag=_wrap_Vector6_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 354: flag=_wrap_Vector6_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 355: flag=_wrap_Vector6_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 356: flag=_wrap_Vector6_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 357: flag=_wrap_Vector6_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 358: flag=_wrap_Vector6_end(resc,resv,argc,(mxArray**)(argv)); break; - case 359: flag=_wrap_Vector6_size(resc,resv,argc,(mxArray**)(argv)); break; - case 360: flag=_wrap_Vector6_data(resc,resv,argc,(mxArray**)(argv)); break; - case 361: flag=_wrap_Vector6_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 362: flag=_wrap_Vector6_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 363: flag=_wrap_Vector6_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 364: flag=_wrap_Vector6_display(resc,resv,argc,(mxArray**)(argv)); break; - case 365: flag=_wrap_Vector6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 366: flag=_wrap_Vector6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 367: flag=_wrap_delete_Vector6(resc,resv,argc,(mxArray**)(argv)); break; - case 368: flag=_wrap_new_Vector10(resc,resv,argc,(mxArray**)(argv)); break; - case 369: flag=_wrap_Vector10_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 370: flag=_wrap_Vector10_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 371: flag=_wrap_Vector10_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 372: flag=_wrap_Vector10_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 373: flag=_wrap_Vector10_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 374: flag=_wrap_Vector10_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 375: flag=_wrap_Vector10_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 376: flag=_wrap_Vector10_end(resc,resv,argc,(mxArray**)(argv)); break; - case 377: flag=_wrap_Vector10_size(resc,resv,argc,(mxArray**)(argv)); break; - case 378: flag=_wrap_Vector10_data(resc,resv,argc,(mxArray**)(argv)); break; - case 379: flag=_wrap_Vector10_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 380: flag=_wrap_Vector10_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 381: flag=_wrap_Vector10_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 382: flag=_wrap_Vector10_display(resc,resv,argc,(mxArray**)(argv)); break; - case 383: flag=_wrap_Vector10_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 384: flag=_wrap_Vector10_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 385: flag=_wrap_delete_Vector10(resc,resv,argc,(mxArray**)(argv)); break; - case 386: flag=_wrap_new_Vector16(resc,resv,argc,(mxArray**)(argv)); break; - case 387: flag=_wrap_Vector16_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 388: flag=_wrap_Vector16_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 389: flag=_wrap_Vector16_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 390: flag=_wrap_Vector16_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 391: flag=_wrap_Vector16_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 392: flag=_wrap_Vector16_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 393: flag=_wrap_Vector16_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 394: flag=_wrap_Vector16_end(resc,resv,argc,(mxArray**)(argv)); break; - case 395: flag=_wrap_Vector16_size(resc,resv,argc,(mxArray**)(argv)); break; - case 396: flag=_wrap_Vector16_data(resc,resv,argc,(mxArray**)(argv)); break; - case 397: flag=_wrap_Vector16_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 398: flag=_wrap_Vector16_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; - case 399: flag=_wrap_Vector16_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 400: flag=_wrap_Vector16_display(resc,resv,argc,(mxArray**)(argv)); break; - case 401: flag=_wrap_Vector16_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 402: flag=_wrap_Vector16_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 403: flag=_wrap_delete_Vector16(resc,resv,argc,(mxArray**)(argv)); break; - case 404: flag=_wrap_new_PositionRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 405: flag=_wrap_PositionRaw_changePoint(resc,resv,argc,(mxArray**)(argv)); break; - case 406: flag=_wrap_PositionRaw_changeRefPoint(resc,resv,argc,(mxArray**)(argv)); break; - case 407: flag=_wrap_PositionRaw_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 408: flag=_wrap_PositionRaw_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 409: flag=_wrap_PositionRaw_changePointOf(resc,resv,argc,(mxArray**)(argv)); break; - case 410: flag=_wrap_PositionRaw_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 411: flag=_wrap_PositionRaw_display(resc,resv,argc,(mxArray**)(argv)); break; - case 412: flag=_wrap_delete_PositionRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 413: flag=_wrap_new_Position(resc,resv,argc,(mxArray**)(argv)); break; - case 414: flag=_wrap_Position_changePoint(resc,resv,argc,(mxArray**)(argv)); break; - case 415: flag=_wrap_Position_changeRefPoint(resc,resv,argc,(mxArray**)(argv)); break; - case 416: flag=_wrap_Position_changeCoordinateFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 417: flag=_wrap_Position_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 418: flag=_wrap_Position_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 419: flag=_wrap_Position_changePointOf(resc,resv,argc,(mxArray**)(argv)); break; - case 420: flag=_wrap_Position_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 421: flag=_wrap_Position_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 422: flag=_wrap_Position_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 423: flag=_wrap_Position_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 424: flag=_wrap_Position_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 425: flag=_wrap_Position_display(resc,resv,argc,(mxArray**)(argv)); break; - case 426: flag=_wrap_Position_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 427: flag=_wrap_delete_Position(resc,resv,argc,(mxArray**)(argv)); break; - case 428: flag=_wrap_new_GeomVector3(resc,resv,argc,(mxArray**)(argv)); break; - case 429: flag=_wrap_GeomVector3_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 430: flag=_wrap_GeomVector3_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 431: flag=_wrap_GeomVector3_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 432: flag=_wrap_GeomVector3_dot(resc,resv,argc,(mxArray**)(argv)); break; - case 433: flag=_wrap_GeomVector3_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 434: flag=_wrap_GeomVector3_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 435: flag=_wrap_GeomVector3_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 436: flag=_wrap_GeomVector3_exp(resc,resv,argc,(mxArray**)(argv)); break; - case 437: flag=_wrap_GeomVector3_cross(resc,resv,argc,(mxArray**)(argv)); break; - case 438: flag=_wrap_delete_GeomVector3(resc,resv,argc,(mxArray**)(argv)); break; - case 439: flag=_wrap_new_SpatialMotionVectorBase(resc,resv,argc,(mxArray**)(argv)); break; - case 440: flag=_wrap_SpatialMotionVectorBase_getLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 441: flag=_wrap_SpatialMotionVectorBase_getAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 442: flag=_wrap_SpatialMotionVectorBase_setLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 443: flag=_wrap_SpatialMotionVectorBase_setAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 444: flag=_wrap_SpatialMotionVectorBase_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 445: flag=_wrap_SpatialMotionVectorBase_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 446: flag=_wrap_SpatialMotionVectorBase_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 447: flag=_wrap_SpatialMotionVectorBase_size(resc,resv,argc,(mxArray**)(argv)); break; - case 448: flag=_wrap_SpatialMotionVectorBase_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 449: flag=_wrap_SpatialMotionVectorBase_changePoint(resc,resv,argc,(mxArray**)(argv)); break; - case 450: flag=_wrap_SpatialMotionVectorBase_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 451: flag=_wrap_SpatialMotionVectorBase_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 452: flag=_wrap_SpatialMotionVectorBase_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 453: flag=_wrap_SpatialMotionVectorBase_dot(resc,resv,argc,(mxArray**)(argv)); break; - case 454: flag=_wrap_SpatialMotionVectorBase_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 455: flag=_wrap_SpatialMotionVectorBase_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 456: flag=_wrap_SpatialMotionVectorBase_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 457: flag=_wrap_SpatialMotionVectorBase_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 458: flag=_wrap_SpatialMotionVectorBase_asVector(resc,resv,argc,(mxArray**)(argv)); break; - case 459: flag=_wrap_SpatialMotionVectorBase_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 460: flag=_wrap_SpatialMotionVectorBase_display(resc,resv,argc,(mxArray**)(argv)); break; - case 461: flag=_wrap_SpatialMotionVectorBase_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 462: flag=_wrap_SpatialMotionVectorBase_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 463: flag=_wrap_delete_SpatialMotionVectorBase(resc,resv,argc,(mxArray**)(argv)); break; - case 464: flag=_wrap_new_SpatialForceVectorBase(resc,resv,argc,(mxArray**)(argv)); break; - case 465: flag=_wrap_SpatialForceVectorBase_getLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 466: flag=_wrap_SpatialForceVectorBase_getAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 467: flag=_wrap_SpatialForceVectorBase_setLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 468: flag=_wrap_SpatialForceVectorBase_setAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; - case 469: flag=_wrap_SpatialForceVectorBase_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 470: flag=_wrap_SpatialForceVectorBase_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 471: flag=_wrap_SpatialForceVectorBase_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 472: flag=_wrap_SpatialForceVectorBase_size(resc,resv,argc,(mxArray**)(argv)); break; - case 473: flag=_wrap_SpatialForceVectorBase_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 474: flag=_wrap_SpatialForceVectorBase_changePoint(resc,resv,argc,(mxArray**)(argv)); break; - case 475: flag=_wrap_SpatialForceVectorBase_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 476: flag=_wrap_SpatialForceVectorBase_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 477: flag=_wrap_SpatialForceVectorBase_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 478: flag=_wrap_SpatialForceVectorBase_dot(resc,resv,argc,(mxArray**)(argv)); break; - case 479: flag=_wrap_SpatialForceVectorBase_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 480: flag=_wrap_SpatialForceVectorBase_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 481: flag=_wrap_SpatialForceVectorBase_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 482: flag=_wrap_SpatialForceVectorBase_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 483: flag=_wrap_SpatialForceVectorBase_asVector(resc,resv,argc,(mxArray**)(argv)); break; - case 484: flag=_wrap_SpatialForceVectorBase_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 485: flag=_wrap_SpatialForceVectorBase_display(resc,resv,argc,(mxArray**)(argv)); break; - case 486: flag=_wrap_SpatialForceVectorBase_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 487: flag=_wrap_SpatialForceVectorBase_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 488: flag=_wrap_delete_SpatialForceVectorBase(resc,resv,argc,(mxArray**)(argv)); break; - case 489: flag=_wrap_new_Dummy(resc,resv,argc,(mxArray**)(argv)); break; - case 490: flag=_wrap_delete_Dummy(resc,resv,argc,(mxArray**)(argv)); break; - case 491: flag=_wrap_new_SpatialMotionVector(resc,resv,argc,(mxArray**)(argv)); break; - case 492: flag=_wrap_SpatialMotionVector_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 493: flag=_wrap_SpatialMotionVector_cross(resc,resv,argc,(mxArray**)(argv)); break; - case 494: flag=_wrap_SpatialMotionVector_asCrossProductMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 495: flag=_wrap_SpatialMotionVector_asCrossProductMatrixWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 496: flag=_wrap_SpatialMotionVector_exp(resc,resv,argc,(mxArray**)(argv)); break; - case 497: flag=_wrap_delete_SpatialMotionVector(resc,resv,argc,(mxArray**)(argv)); break; - case 498: flag=_wrap_new_SpatialForceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 499: flag=_wrap_delete_SpatialForceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 500: flag=_wrap_SpatialForceVector_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 501: flag=_wrap_new_Twist(resc,resv,argc,(mxArray**)(argv)); break; - case 502: flag=_wrap_Twist_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 503: flag=_wrap_Twist_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 504: flag=_wrap_Twist_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 505: flag=_wrap_Twist_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 506: flag=_wrap_delete_Twist(resc,resv,argc,(mxArray**)(argv)); break; - case 507: flag=_wrap_new_Wrench(resc,resv,argc,(mxArray**)(argv)); break; - case 508: flag=_wrap_Wrench_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 509: flag=_wrap_Wrench_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 510: flag=_wrap_Wrench_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 511: flag=_wrap_delete_Wrench(resc,resv,argc,(mxArray**)(argv)); break; - case 512: flag=_wrap_new_SpatialMomentum(resc,resv,argc,(mxArray**)(argv)); break; - case 513: flag=_wrap_SpatialMomentum_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 514: flag=_wrap_SpatialMomentum_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 515: flag=_wrap_SpatialMomentum_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 516: flag=_wrap_delete_SpatialMomentum(resc,resv,argc,(mxArray**)(argv)); break; - case 517: flag=_wrap_new_SpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 518: flag=_wrap_SpatialAcc_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 519: flag=_wrap_SpatialAcc_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 520: flag=_wrap_SpatialAcc_uminus(resc,resv,argc,(mxArray**)(argv)); break; - case 521: flag=_wrap_delete_SpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 522: flag=_wrap_new_ClassicalAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 523: flag=_wrap_ClassicalAcc_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 524: flag=_wrap_ClassicalAcc_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 525: flag=_wrap_ClassicalAcc_fromSpatial(resc,resv,argc,(mxArray**)(argv)); break; - case 526: flag=_wrap_ClassicalAcc_toSpatial(resc,resv,argc,(mxArray**)(argv)); break; - case 527: flag=_wrap_delete_ClassicalAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 528: flag=_wrap_new_Direction(resc,resv,argc,(mxArray**)(argv)); break; - case 529: flag=_wrap_Direction_Normalize(resc,resv,argc,(mxArray**)(argv)); break; - case 530: flag=_wrap_Direction_isParallel(resc,resv,argc,(mxArray**)(argv)); break; - case 531: flag=_wrap_Direction_isPerpendicular(resc,resv,argc,(mxArray**)(argv)); break; - case 532: flag=_wrap_Direction_reverse(resc,resv,argc,(mxArray**)(argv)); break; - case 533: flag=_wrap_Direction_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 534: flag=_wrap_Direction_display(resc,resv,argc,(mxArray**)(argv)); break; - case 535: flag=_wrap_Direction_Default(resc,resv,argc,(mxArray**)(argv)); break; - case 536: flag=_wrap_delete_Direction(resc,resv,argc,(mxArray**)(argv)); break; - case 537: flag=_wrap_new_Axis(resc,resv,argc,(mxArray**)(argv)); break; - case 538: flag=_wrap_Axis_getDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 539: flag=_wrap_Axis_getOrigin(resc,resv,argc,(mxArray**)(argv)); break; - case 540: flag=_wrap_Axis_setDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 541: flag=_wrap_Axis_setOrigin(resc,resv,argc,(mxArray**)(argv)); break; - case 542: flag=_wrap_Axis_getRotationTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 543: flag=_wrap_Axis_getRotationTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 544: flag=_wrap_Axis_getRotationTwist(resc,resv,argc,(mxArray**)(argv)); break; - case 545: flag=_wrap_Axis_getRotationSpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 546: flag=_wrap_Axis_getTranslationTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 547: flag=_wrap_Axis_getTranslationTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 548: flag=_wrap_Axis_getTranslationTwist(resc,resv,argc,(mxArray**)(argv)); break; - case 549: flag=_wrap_Axis_getTranslationSpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 550: flag=_wrap_Axis_isParallel(resc,resv,argc,(mxArray**)(argv)); break; - case 551: flag=_wrap_Axis_reverse(resc,resv,argc,(mxArray**)(argv)); break; - case 552: flag=_wrap_Axis_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 553: flag=_wrap_Axis_display(resc,resv,argc,(mxArray**)(argv)); break; - case 554: flag=_wrap_delete_Axis(resc,resv,argc,(mxArray**)(argv)); break; - case 555: flag=_wrap_new_RotationalInertiaRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 556: flag=_wrap_RotationalInertiaRaw_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 557: flag=_wrap_delete_RotationalInertiaRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 558: flag=_wrap_new_SpatialInertiaRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 559: flag=_wrap_SpatialInertiaRaw_fromRotationalInertiaWrtCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; - case 560: flag=_wrap_SpatialInertiaRaw_getMass(resc,resv,argc,(mxArray**)(argv)); break; - case 561: flag=_wrap_SpatialInertiaRaw_getCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; - case 562: flag=_wrap_SpatialInertiaRaw_getRotationalInertiaWrtFrameOrigin(resc,resv,argc,(mxArray**)(argv)); break; - case 563: flag=_wrap_SpatialInertiaRaw_getRotationalInertiaWrtCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; - case 564: flag=_wrap_SpatialInertiaRaw_combine(resc,resv,argc,(mxArray**)(argv)); break; - case 565: flag=_wrap_SpatialInertiaRaw_multiply(resc,resv,argc,(mxArray**)(argv)); break; - case 566: flag=_wrap_SpatialInertiaRaw_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 567: flag=_wrap_delete_SpatialInertiaRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 568: flag=_wrap_new_SpatialInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 569: flag=_wrap_SpatialInertia_combine(resc,resv,argc,(mxArray**)(argv)); break; - case 570: flag=_wrap_SpatialInertia_asMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 571: flag=_wrap_SpatialInertia_applyInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 572: flag=_wrap_SpatialInertia_getInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 573: flag=_wrap_SpatialInertia_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 574: flag=_wrap_SpatialInertia_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 575: flag=_wrap_SpatialInertia_biasWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 576: flag=_wrap_SpatialInertia_biasWrenchDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 577: flag=_wrap_SpatialInertia_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 578: flag=_wrap_SpatialInertia_asVector(resc,resv,argc,(mxArray**)(argv)); break; - case 579: flag=_wrap_SpatialInertia_fromVector(resc,resv,argc,(mxArray**)(argv)); break; - case 580: flag=_wrap_SpatialInertia_isPhysicallyConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 581: flag=_wrap_SpatialInertia_momentumRegressor(resc,resv,argc,(mxArray**)(argv)); break; - case 582: flag=_wrap_SpatialInertia_momentumDerivativeRegressor(resc,resv,argc,(mxArray**)(argv)); break; - case 583: flag=_wrap_SpatialInertia_momentumDerivativeSlotineLiRegressor(resc,resv,argc,(mxArray**)(argv)); break; - case 584: flag=_wrap_delete_SpatialInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 585: flag=_wrap_new_ArticulatedBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 586: flag=_wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 587: flag=_wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 588: flag=_wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 589: flag=_wrap_ArticulatedBodyInertia_combine(resc,resv,argc,(mxArray**)(argv)); break; - case 590: flag=_wrap_ArticulatedBodyInertia_applyInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 591: flag=_wrap_ArticulatedBodyInertia_asMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 592: flag=_wrap_ArticulatedBodyInertia_getInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 593: flag=_wrap_ArticulatedBodyInertia_plus(resc,resv,argc,(mxArray**)(argv)); break; - case 594: flag=_wrap_ArticulatedBodyInertia_minus(resc,resv,argc,(mxArray**)(argv)); break; - case 595: flag=_wrap_ArticulatedBodyInertia_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 596: flag=_wrap_ArticulatedBodyInertia_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 597: flag=_wrap_ArticulatedBodyInertia_ABADyadHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 598: flag=_wrap_ArticulatedBodyInertia_ABADyadHelperLin(resc,resv,argc,(mxArray**)(argv)); break; - case 599: flag=_wrap_delete_ArticulatedBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 600: flag=_wrap_RigidBodyInertiaNonLinearParametrization_mass_get(resc,resv,argc,(mxArray**)(argv)); break; - case 601: flag=_wrap_RigidBodyInertiaNonLinearParametrization_mass_set(resc,resv,argc,(mxArray**)(argv)); break; - case 602: flag=_wrap_RigidBodyInertiaNonLinearParametrization_com_get(resc,resv,argc,(mxArray**)(argv)); break; - case 603: flag=_wrap_RigidBodyInertiaNonLinearParametrization_com_set(resc,resv,argc,(mxArray**)(argv)); break; - case 604: flag=_wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get(resc,resv,argc,(mxArray**)(argv)); break; - case 605: flag=_wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set(resc,resv,argc,(mxArray**)(argv)); break; - case 606: flag=_wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get(resc,resv,argc,(mxArray**)(argv)); break; - case 607: flag=_wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set(resc,resv,argc,(mxArray**)(argv)); break; - case 608: flag=_wrap_RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 609: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 610: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 611: flag=_wrap_RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 612: flag=_wrap_RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 613: flag=_wrap_RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; - case 614: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; - case 615: flag=_wrap_RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; - case 616: flag=_wrap_new_RigidBodyInertiaNonLinearParametrization(resc,resv,argc,(mxArray**)(argv)); break; - case 617: flag=_wrap_delete_RigidBodyInertiaNonLinearParametrization(resc,resv,argc,(mxArray**)(argv)); break; - case 618: flag=_wrap_new_RotationRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 619: flag=_wrap_RotationRaw_changeOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 620: flag=_wrap_RotationRaw_changeRefOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 621: flag=_wrap_RotationRaw_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 622: flag=_wrap_RotationRaw_inverse2(resc,resv,argc,(mxArray**)(argv)); break; - case 623: flag=_wrap_RotationRaw_changeCoordFrameOf(resc,resv,argc,(mxArray**)(argv)); break; - case 624: flag=_wrap_RotationRaw_RotX(resc,resv,argc,(mxArray**)(argv)); break; - case 625: flag=_wrap_RotationRaw_RotY(resc,resv,argc,(mxArray**)(argv)); break; - case 626: flag=_wrap_RotationRaw_RotZ(resc,resv,argc,(mxArray**)(argv)); break; - case 627: flag=_wrap_RotationRaw_RPY(resc,resv,argc,(mxArray**)(argv)); break; - case 628: flag=_wrap_RotationRaw_Identity(resc,resv,argc,(mxArray**)(argv)); break; - case 629: flag=_wrap_RotationRaw_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 630: flag=_wrap_RotationRaw_display(resc,resv,argc,(mxArray**)(argv)); break; - case 631: flag=_wrap_delete_RotationRaw(resc,resv,argc,(mxArray**)(argv)); break; - case 632: flag=_wrap_new_Rotation(resc,resv,argc,(mxArray**)(argv)); break; - case 633: flag=_wrap_Rotation_changeOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 634: flag=_wrap_Rotation_changeRefOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 635: flag=_wrap_Rotation_changeCoordinateFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 636: flag=_wrap_Rotation_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 637: flag=_wrap_Rotation_inverse2(resc,resv,argc,(mxArray**)(argv)); break; - case 638: flag=_wrap_Rotation_changeCoordFrameOf(resc,resv,argc,(mxArray**)(argv)); break; - case 639: flag=_wrap_Rotation_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 640: flag=_wrap_Rotation_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 641: flag=_wrap_Rotation_log(resc,resv,argc,(mxArray**)(argv)); break; - case 642: flag=_wrap_Rotation_fromQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 643: flag=_wrap_Rotation_getRPY(resc,resv,argc,(mxArray**)(argv)); break; - case 644: flag=_wrap_Rotation_asRPY(resc,resv,argc,(mxArray**)(argv)); break; - case 645: flag=_wrap_Rotation_getQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 646: flag=_wrap_Rotation_asQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 647: flag=_wrap_Rotation_RotX(resc,resv,argc,(mxArray**)(argv)); break; - case 648: flag=_wrap_Rotation_RotY(resc,resv,argc,(mxArray**)(argv)); break; - case 649: flag=_wrap_Rotation_RotZ(resc,resv,argc,(mxArray**)(argv)); break; - case 650: flag=_wrap_Rotation_RotAxis(resc,resv,argc,(mxArray**)(argv)); break; - case 651: flag=_wrap_Rotation_RotAxisDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 652: flag=_wrap_Rotation_RPY(resc,resv,argc,(mxArray**)(argv)); break; - case 653: flag=_wrap_Rotation_RPYRightTrivializedDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 654: flag=_wrap_Rotation_RPYRightTrivializedDerivativeRateOfChange(resc,resv,argc,(mxArray**)(argv)); break; - case 655: flag=_wrap_Rotation_RPYRightTrivializedDerivativeInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 656: flag=_wrap_Rotation_RPYRightTrivializedDerivativeInverseRateOfChange(resc,resv,argc,(mxArray**)(argv)); break; - case 657: flag=_wrap_Rotation_QuaternionRightTrivializedDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 658: flag=_wrap_Rotation_QuaternionRightTrivializedDerivativeInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 659: flag=_wrap_Rotation_Identity(resc,resv,argc,(mxArray**)(argv)); break; - case 660: flag=_wrap_Rotation_RotationFromQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 661: flag=_wrap_Rotation_leftJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 662: flag=_wrap_Rotation_leftJacobianInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 663: flag=_wrap_Rotation_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 664: flag=_wrap_Rotation_display(resc,resv,argc,(mxArray**)(argv)); break; - case 665: flag=_wrap_delete_Rotation(resc,resv,argc,(mxArray**)(argv)); break; - case 666: flag=_wrap_new_Transform(resc,resv,argc,(mxArray**)(argv)); break; - case 667: flag=_wrap_Transform_fromHomogeneousTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 668: flag=_wrap_Transform_getRotation(resc,resv,argc,(mxArray**)(argv)); break; - case 669: flag=_wrap_Transform_getPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 670: flag=_wrap_Transform_setRotation(resc,resv,argc,(mxArray**)(argv)); break; - case 671: flag=_wrap_Transform_setPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 672: flag=_wrap_Transform_compose(resc,resv,argc,(mxArray**)(argv)); break; - case 673: flag=_wrap_Transform_inverse2(resc,resv,argc,(mxArray**)(argv)); break; - case 674: flag=_wrap_Transform_inverse(resc,resv,argc,(mxArray**)(argv)); break; - case 675: flag=_wrap_Transform_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 676: flag=_wrap_Transform_Identity(resc,resv,argc,(mxArray**)(argv)); break; - case 677: flag=_wrap_Transform_asHomogeneousTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 678: flag=_wrap_Transform_asAdjointTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 679: flag=_wrap_Transform_asAdjointTransformWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 680: flag=_wrap_Transform_log(resc,resv,argc,(mxArray**)(argv)); break; - case 681: flag=_wrap_Transform_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 682: flag=_wrap_Transform_display(resc,resv,argc,(mxArray**)(argv)); break; - case 683: flag=_wrap_delete_Transform(resc,resv,argc,(mxArray**)(argv)); break; - case 684: flag=_wrap_new_TransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 685: flag=_wrap_delete_TransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 686: flag=_wrap_TransformDerivative_getRotationDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 687: flag=_wrap_TransformDerivative_getPositionDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 688: flag=_wrap_TransformDerivative_setRotationDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 689: flag=_wrap_TransformDerivative_setPositionDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 690: flag=_wrap_TransformDerivative_Zero(resc,resv,argc,(mxArray**)(argv)); break; - case 691: flag=_wrap_TransformDerivative_asHomogeneousTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 692: flag=_wrap_TransformDerivative_asAdjointTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 693: flag=_wrap_TransformDerivative_asAdjointTransformWrenchDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 694: flag=_wrap_TransformDerivative_mtimes(resc,resv,argc,(mxArray**)(argv)); break; - case 695: flag=_wrap_TransformDerivative_derivativeOfInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 696: flag=_wrap_TransformDerivative_transform(resc,resv,argc,(mxArray**)(argv)); break; - case 697: flag=_wrap_dynamic_extent_get(resc,resv,argc,(mxArray**)(argv)); break; - case 698: flag=_wrap_DynamicSpan_extent_get(resc,resv,argc,(mxArray**)(argv)); break; - case 699: flag=_wrap_new_DynamicSpan(resc,resv,argc,(mxArray**)(argv)); break; - case 700: flag=_wrap_delete_DynamicSpan(resc,resv,argc,(mxArray**)(argv)); break; - case 701: flag=_wrap_DynamicSpan_first(resc,resv,argc,(mxArray**)(argv)); break; - case 702: flag=_wrap_DynamicSpan_last(resc,resv,argc,(mxArray**)(argv)); break; - case 703: flag=_wrap_DynamicSpan_subspan(resc,resv,argc,(mxArray**)(argv)); break; - case 704: flag=_wrap_DynamicSpan_size(resc,resv,argc,(mxArray**)(argv)); break; - case 705: flag=_wrap_DynamicSpan_size_bytes(resc,resv,argc,(mxArray**)(argv)); break; - case 706: flag=_wrap_DynamicSpan_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 707: flag=_wrap_DynamicSpan_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 708: flag=_wrap_DynamicSpan_getVal(resc,resv,argc,(mxArray**)(argv)); break; - case 709: flag=_wrap_DynamicSpan_setVal(resc,resv,argc,(mxArray**)(argv)); break; - case 710: flag=_wrap_DynamicSpan_at(resc,resv,argc,(mxArray**)(argv)); break; - case 711: flag=_wrap_DynamicSpan_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 712: flag=_wrap_DynamicSpan_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 713: flag=_wrap_DynamicSpan_end(resc,resv,argc,(mxArray**)(argv)); break; - case 714: flag=_wrap_DynamicSpan_cbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 715: flag=_wrap_DynamicSpan_cend(resc,resv,argc,(mxArray**)(argv)); break; - case 716: flag=_wrap_DynamicSpan_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 717: flag=_wrap_DynamicSpan_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 718: flag=_wrap_DynamicSpan_crbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 719: flag=_wrap_DynamicSpan_crend(resc,resv,argc,(mxArray**)(argv)); break; - case 720: flag=_wrap_new_DynamicMatrixView(resc,resv,argc,(mxArray**)(argv)); break; - case 721: flag=_wrap_DynamicMatrixView_storageOrder(resc,resv,argc,(mxArray**)(argv)); break; - case 722: flag=_wrap_DynamicMatrixView_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 723: flag=_wrap_DynamicMatrixView_rows(resc,resv,argc,(mxArray**)(argv)); break; - case 724: flag=_wrap_DynamicMatrixView_cols(resc,resv,argc,(mxArray**)(argv)); break; - case 725: flag=_wrap_DynamicMatrixView_block(resc,resv,argc,(mxArray**)(argv)); break; - case 726: flag=_wrap_delete_DynamicMatrixView(resc,resv,argc,(mxArray**)(argv)); break; - case 727: flag=_wrap_LINK_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; - case 728: flag=_wrap_LINK_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; - case 729: flag=_wrap_LINK_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; - case 730: flag=_wrap_LINK_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; - case 731: flag=_wrap_JOINT_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; - case 732: flag=_wrap_JOINT_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; - case 733: flag=_wrap_JOINT_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; - case 734: flag=_wrap_JOINT_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; - case 735: flag=_wrap_DOF_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; - case 736: flag=_wrap_DOF_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; - case 737: flag=_wrap_DOF_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; - case 738: flag=_wrap_DOF_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; - case 739: flag=_wrap_FRAME_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; - case 740: flag=_wrap_FRAME_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; - case 741: flag=_wrap_FRAME_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; - case 742: flag=_wrap_FRAME_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; - case 743: flag=_wrap_TRAVERSAL_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; - case 744: flag=_wrap_TRAVERSAL_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; - case 745: flag=_wrap_new_LinkPositions(resc,resv,argc,(mxArray**)(argv)); break; - case 746: flag=_wrap_LinkPositions_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 747: flag=_wrap_LinkPositions_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 748: flag=_wrap_LinkPositions_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 749: flag=_wrap_LinkPositions_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 750: flag=_wrap_LinkPositions_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 751: flag=_wrap_delete_LinkPositions(resc,resv,argc,(mxArray**)(argv)); break; - case 752: flag=_wrap_new_LinkWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 753: flag=_wrap_LinkWrenches_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 754: flag=_wrap_LinkWrenches_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 755: flag=_wrap_LinkWrenches_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 756: flag=_wrap_LinkWrenches_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 757: flag=_wrap_LinkWrenches_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 758: flag=_wrap_LinkWrenches_zero(resc,resv,argc,(mxArray**)(argv)); break; - case 759: flag=_wrap_delete_LinkWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 760: flag=_wrap_new_LinkInertias(resc,resv,argc,(mxArray**)(argv)); break; - case 761: flag=_wrap_LinkInertias_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 762: flag=_wrap_LinkInertias_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 763: flag=_wrap_LinkInertias_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 764: flag=_wrap_delete_LinkInertias(resc,resv,argc,(mxArray**)(argv)); break; - case 765: flag=_wrap_new_LinkArticulatedBodyInertias(resc,resv,argc,(mxArray**)(argv)); break; - case 766: flag=_wrap_LinkArticulatedBodyInertias_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 767: flag=_wrap_LinkArticulatedBodyInertias_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 768: flag=_wrap_LinkArticulatedBodyInertias_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 769: flag=_wrap_delete_LinkArticulatedBodyInertias(resc,resv,argc,(mxArray**)(argv)); break; - case 770: flag=_wrap_new_LinkVelArray(resc,resv,argc,(mxArray**)(argv)); break; - case 771: flag=_wrap_LinkVelArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 772: flag=_wrap_LinkVelArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 773: flag=_wrap_LinkVelArray_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 774: flag=_wrap_LinkVelArray_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 775: flag=_wrap_LinkVelArray_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 776: flag=_wrap_delete_LinkVelArray(resc,resv,argc,(mxArray**)(argv)); break; - case 777: flag=_wrap_new_LinkAccArray(resc,resv,argc,(mxArray**)(argv)); break; - case 778: flag=_wrap_LinkAccArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 779: flag=_wrap_LinkAccArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 780: flag=_wrap_LinkAccArray_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 781: flag=_wrap_LinkAccArray_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 782: flag=_wrap_LinkAccArray_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 783: flag=_wrap_delete_LinkAccArray(resc,resv,argc,(mxArray**)(argv)); break; - case 784: flag=_wrap_new_Link(resc,resv,argc,(mxArray**)(argv)); break; - case 785: flag=_wrap_Link_inertia(resc,resv,argc,(mxArray**)(argv)); break; - case 786: flag=_wrap_Link_setInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 787: flag=_wrap_Link_getInertia(resc,resv,argc,(mxArray**)(argv)); break; - case 788: flag=_wrap_Link_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 789: flag=_wrap_Link_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 790: flag=_wrap_delete_Link(resc,resv,argc,(mxArray**)(argv)); break; - case 791: flag=_wrap_delete_IJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 792: flag=_wrap_IJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 793: flag=_wrap_IJoint_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 794: flag=_wrap_IJoint_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 795: flag=_wrap_IJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 796: flag=_wrap_IJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 797: flag=_wrap_IJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 798: flag=_wrap_IJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 799: flag=_wrap_IJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 800: flag=_wrap_IJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 801: flag=_wrap_IJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 802: flag=_wrap_IJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 803: flag=_wrap_IJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 804: flag=_wrap_IJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 805: flag=_wrap_IJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; - case 806: flag=_wrap_IJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 807: flag=_wrap_IJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 808: flag=_wrap_IJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; - case 809: flag=_wrap_IJoint_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 810: flag=_wrap_IJoint_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 811: flag=_wrap_IJoint_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 812: flag=_wrap_IJoint_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 813: flag=_wrap_IJoint_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 814: flag=_wrap_IJoint_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 815: flag=_wrap_IJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 816: flag=_wrap_IJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 817: flag=_wrap_IJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 818: flag=_wrap_IJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 819: flag=_wrap_IJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 820: flag=_wrap_IJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 821: flag=_wrap_IJoint_isRevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 822: flag=_wrap_IJoint_isFixedJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 823: flag=_wrap_IJoint_isPrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 824: flag=_wrap_IJoint_asRevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 825: flag=_wrap_IJoint_asFixedJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 826: flag=_wrap_IJoint_asPrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 827: flag=_wrap_new_FixedJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 828: flag=_wrap_delete_FixedJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 829: flag=_wrap_FixedJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 830: flag=_wrap_FixedJoint_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 831: flag=_wrap_FixedJoint_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 832: flag=_wrap_FixedJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 833: flag=_wrap_FixedJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 834: flag=_wrap_FixedJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 835: flag=_wrap_FixedJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 836: flag=_wrap_FixedJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 837: flag=_wrap_FixedJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 838: flag=_wrap_FixedJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 839: flag=_wrap_FixedJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 840: flag=_wrap_FixedJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 841: flag=_wrap_FixedJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 842: flag=_wrap_FixedJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; - case 843: flag=_wrap_FixedJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 844: flag=_wrap_FixedJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 845: flag=_wrap_FixedJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; - case 846: flag=_wrap_FixedJoint_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 847: flag=_wrap_FixedJoint_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 848: flag=_wrap_FixedJoint_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 849: flag=_wrap_FixedJoint_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 850: flag=_wrap_FixedJoint_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 851: flag=_wrap_FixedJoint_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 852: flag=_wrap_FixedJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 853: flag=_wrap_FixedJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 854: flag=_wrap_FixedJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 855: flag=_wrap_FixedJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 856: flag=_wrap_FixedJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 857: flag=_wrap_FixedJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 858: flag=_wrap_delete_MovableJointImpl1(resc,resv,argc,(mxArray**)(argv)); break; - case 859: flag=_wrap_MovableJointImpl1_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 860: flag=_wrap_MovableJointImpl1_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 861: flag=_wrap_MovableJointImpl1_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 862: flag=_wrap_MovableJointImpl1_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 863: flag=_wrap_MovableJointImpl1_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 864: flag=_wrap_MovableJointImpl1_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 865: flag=_wrap_MovableJointImpl1_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 866: flag=_wrap_MovableJointImpl1_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 867: flag=_wrap_delete_MovableJointImpl2(resc,resv,argc,(mxArray**)(argv)); break; - case 868: flag=_wrap_MovableJointImpl2_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 869: flag=_wrap_MovableJointImpl2_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 870: flag=_wrap_MovableJointImpl2_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 871: flag=_wrap_MovableJointImpl2_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 872: flag=_wrap_MovableJointImpl2_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 873: flag=_wrap_MovableJointImpl2_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 874: flag=_wrap_MovableJointImpl2_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 875: flag=_wrap_MovableJointImpl2_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 876: flag=_wrap_delete_MovableJointImpl3(resc,resv,argc,(mxArray**)(argv)); break; - case 877: flag=_wrap_MovableJointImpl3_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 878: flag=_wrap_MovableJointImpl3_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 879: flag=_wrap_MovableJointImpl3_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 880: flag=_wrap_MovableJointImpl3_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 881: flag=_wrap_MovableJointImpl3_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 882: flag=_wrap_MovableJointImpl3_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 883: flag=_wrap_MovableJointImpl3_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 884: flag=_wrap_MovableJointImpl3_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 885: flag=_wrap_delete_MovableJointImpl4(resc,resv,argc,(mxArray**)(argv)); break; - case 886: flag=_wrap_MovableJointImpl4_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 887: flag=_wrap_MovableJointImpl4_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 888: flag=_wrap_MovableJointImpl4_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 889: flag=_wrap_MovableJointImpl4_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 890: flag=_wrap_MovableJointImpl4_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 891: flag=_wrap_MovableJointImpl4_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 892: flag=_wrap_MovableJointImpl4_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 893: flag=_wrap_MovableJointImpl4_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 894: flag=_wrap_delete_MovableJointImpl5(resc,resv,argc,(mxArray**)(argv)); break; - case 895: flag=_wrap_MovableJointImpl5_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 896: flag=_wrap_MovableJointImpl5_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 897: flag=_wrap_MovableJointImpl5_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 898: flag=_wrap_MovableJointImpl5_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 899: flag=_wrap_MovableJointImpl5_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 900: flag=_wrap_MovableJointImpl5_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 901: flag=_wrap_MovableJointImpl5_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 902: flag=_wrap_MovableJointImpl5_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 903: flag=_wrap_delete_MovableJointImpl6(resc,resv,argc,(mxArray**)(argv)); break; - case 904: flag=_wrap_MovableJointImpl6_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 905: flag=_wrap_MovableJointImpl6_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 906: flag=_wrap_MovableJointImpl6_setIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 907: flag=_wrap_MovableJointImpl6_getIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 908: flag=_wrap_MovableJointImpl6_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 909: flag=_wrap_MovableJointImpl6_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 910: flag=_wrap_MovableJointImpl6_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 911: flag=_wrap_MovableJointImpl6_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; - case 912: flag=_wrap_new_RevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 913: flag=_wrap_delete_RevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 914: flag=_wrap_RevoluteJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 915: flag=_wrap_RevoluteJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 916: flag=_wrap_RevoluteJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 917: flag=_wrap_RevoluteJoint_setAxis(resc,resv,argc,(mxArray**)(argv)); break; - case 918: flag=_wrap_RevoluteJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 919: flag=_wrap_RevoluteJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 920: flag=_wrap_RevoluteJoint_getAxis(resc,resv,argc,(mxArray**)(argv)); break; - case 921: flag=_wrap_RevoluteJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 922: flag=_wrap_RevoluteJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 923: flag=_wrap_RevoluteJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 924: flag=_wrap_RevoluteJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 925: flag=_wrap_RevoluteJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 926: flag=_wrap_RevoluteJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; - case 927: flag=_wrap_RevoluteJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 928: flag=_wrap_RevoluteJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 929: flag=_wrap_RevoluteJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 930: flag=_wrap_RevoluteJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; - case 931: flag=_wrap_RevoluteJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 932: flag=_wrap_RevoluteJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 933: flag=_wrap_RevoluteJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 934: flag=_wrap_RevoluteJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 935: flag=_wrap_RevoluteJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 936: flag=_wrap_RevoluteJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 937: flag=_wrap_new_PrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 938: flag=_wrap_delete_PrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 939: flag=_wrap_PrismaticJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 940: flag=_wrap_PrismaticJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 941: flag=_wrap_PrismaticJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 942: flag=_wrap_PrismaticJoint_setAxis(resc,resv,argc,(mxArray**)(argv)); break; - case 943: flag=_wrap_PrismaticJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 944: flag=_wrap_PrismaticJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 945: flag=_wrap_PrismaticJoint_getAxis(resc,resv,argc,(mxArray**)(argv)); break; - case 946: flag=_wrap_PrismaticJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 947: flag=_wrap_PrismaticJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 948: flag=_wrap_PrismaticJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; - case 949: flag=_wrap_PrismaticJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; - case 950: flag=_wrap_PrismaticJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 951: flag=_wrap_PrismaticJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; - case 952: flag=_wrap_PrismaticJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 953: flag=_wrap_PrismaticJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 954: flag=_wrap_PrismaticJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 955: flag=_wrap_PrismaticJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; - case 956: flag=_wrap_PrismaticJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 957: flag=_wrap_PrismaticJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 958: flag=_wrap_PrismaticJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 959: flag=_wrap_PrismaticJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 960: flag=_wrap_PrismaticJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; - case 961: flag=_wrap_PrismaticJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 962: flag=_wrap_new_Traversal(resc,resv,argc,(mxArray**)(argv)); break; - case 963: flag=_wrap_delete_Traversal(resc,resv,argc,(mxArray**)(argv)); break; - case 964: flag=_wrap_Traversal_getNrOfVisitedLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 965: flag=_wrap_Traversal_getLink(resc,resv,argc,(mxArray**)(argv)); break; - case 966: flag=_wrap_Traversal_getBaseLink(resc,resv,argc,(mxArray**)(argv)); break; - case 967: flag=_wrap_Traversal_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 968: flag=_wrap_Traversal_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 969: flag=_wrap_Traversal_getParentLinkFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 970: flag=_wrap_Traversal_getParentJointFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 971: flag=_wrap_Traversal_getTraversalIndexFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 972: flag=_wrap_Traversal_reset(resc,resv,argc,(mxArray**)(argv)); break; - case 973: flag=_wrap_Traversal_addTraversalBase(resc,resv,argc,(mxArray**)(argv)); break; - case 974: flag=_wrap_Traversal_addTraversalElement(resc,resv,argc,(mxArray**)(argv)); break; - case 975: flag=_wrap_Traversal_isParentOf(resc,resv,argc,(mxArray**)(argv)); break; - case 976: flag=_wrap_Traversal_getChildLinkIndexFromJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 977: flag=_wrap_Traversal_getParentLinkIndexFromJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 978: flag=_wrap_Traversal_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 979: flag=_wrap_new_Material(resc,resv,argc,(mxArray**)(argv)); break; - case 980: flag=_wrap_Material_name(resc,resv,argc,(mxArray**)(argv)); break; - case 981: flag=_wrap_Material_hasColor(resc,resv,argc,(mxArray**)(argv)); break; - case 982: flag=_wrap_Material_color(resc,resv,argc,(mxArray**)(argv)); break; - case 983: flag=_wrap_Material_setColor(resc,resv,argc,(mxArray**)(argv)); break; - case 984: flag=_wrap_Material_hasTexture(resc,resv,argc,(mxArray**)(argv)); break; - case 985: flag=_wrap_Material_texture(resc,resv,argc,(mxArray**)(argv)); break; - case 986: flag=_wrap_Material_setTexture(resc,resv,argc,(mxArray**)(argv)); break; - case 987: flag=_wrap_delete_Material(resc,resv,argc,(mxArray**)(argv)); break; - case 988: flag=_wrap_delete_SolidShape(resc,resv,argc,(mxArray**)(argv)); break; - case 989: flag=_wrap_SolidShape_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 990: flag=_wrap_SolidShape_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 991: flag=_wrap_SolidShape_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 992: flag=_wrap_SolidShape_isNameValid(resc,resv,argc,(mxArray**)(argv)); break; - case 993: flag=_wrap_SolidShape_getLink_H_geometry(resc,resv,argc,(mxArray**)(argv)); break; - case 994: flag=_wrap_SolidShape_setLink_H_geometry(resc,resv,argc,(mxArray**)(argv)); break; - case 995: flag=_wrap_SolidShape_isMaterialSet(resc,resv,argc,(mxArray**)(argv)); break; - case 996: flag=_wrap_SolidShape_getMaterial(resc,resv,argc,(mxArray**)(argv)); break; - case 997: flag=_wrap_SolidShape_setMaterial(resc,resv,argc,(mxArray**)(argv)); break; - case 998: flag=_wrap_SolidShape_isSphere(resc,resv,argc,(mxArray**)(argv)); break; - case 999: flag=_wrap_SolidShape_isBox(resc,resv,argc,(mxArray**)(argv)); break; - case 1000: flag=_wrap_SolidShape_isCylinder(resc,resv,argc,(mxArray**)(argv)); break; - case 1001: flag=_wrap_SolidShape_isExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; - case 1002: flag=_wrap_SolidShape_asSphere(resc,resv,argc,(mxArray**)(argv)); break; - case 1003: flag=_wrap_SolidShape_asBox(resc,resv,argc,(mxArray**)(argv)); break; - case 1004: flag=_wrap_SolidShape_asCylinder(resc,resv,argc,(mxArray**)(argv)); break; - case 1005: flag=_wrap_SolidShape_asExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; - case 1006: flag=_wrap_delete_Sphere(resc,resv,argc,(mxArray**)(argv)); break; - case 1007: flag=_wrap_Sphere_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1008: flag=_wrap_Sphere_getRadius(resc,resv,argc,(mxArray**)(argv)); break; - case 1009: flag=_wrap_Sphere_setRadius(resc,resv,argc,(mxArray**)(argv)); break; - case 1010: flag=_wrap_new_Sphere(resc,resv,argc,(mxArray**)(argv)); break; - case 1011: flag=_wrap_delete_Box(resc,resv,argc,(mxArray**)(argv)); break; - case 1012: flag=_wrap_Box_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1013: flag=_wrap_Box_getX(resc,resv,argc,(mxArray**)(argv)); break; - case 1014: flag=_wrap_Box_setX(resc,resv,argc,(mxArray**)(argv)); break; - case 1015: flag=_wrap_Box_getY(resc,resv,argc,(mxArray**)(argv)); break; - case 1016: flag=_wrap_Box_setY(resc,resv,argc,(mxArray**)(argv)); break; - case 1017: flag=_wrap_Box_getZ(resc,resv,argc,(mxArray**)(argv)); break; - case 1018: flag=_wrap_Box_setZ(resc,resv,argc,(mxArray**)(argv)); break; - case 1019: flag=_wrap_new_Box(resc,resv,argc,(mxArray**)(argv)); break; - case 1020: flag=_wrap_delete_Cylinder(resc,resv,argc,(mxArray**)(argv)); break; - case 1021: flag=_wrap_Cylinder_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1022: flag=_wrap_Cylinder_getLength(resc,resv,argc,(mxArray**)(argv)); break; - case 1023: flag=_wrap_Cylinder_setLength(resc,resv,argc,(mxArray**)(argv)); break; - case 1024: flag=_wrap_Cylinder_getRadius(resc,resv,argc,(mxArray**)(argv)); break; - case 1025: flag=_wrap_Cylinder_setRadius(resc,resv,argc,(mxArray**)(argv)); break; - case 1026: flag=_wrap_new_Cylinder(resc,resv,argc,(mxArray**)(argv)); break; - case 1027: flag=_wrap_delete_ExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; - case 1028: flag=_wrap_ExternalMesh_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1029: flag=_wrap_ExternalMesh_getFilename(resc,resv,argc,(mxArray**)(argv)); break; - case 1030: flag=_wrap_ExternalMesh_getFileLocationOnLocalFileSystem(resc,resv,argc,(mxArray**)(argv)); break; - case 1031: flag=_wrap_ExternalMesh_setFilename(resc,resv,argc,(mxArray**)(argv)); break; - case 1032: flag=_wrap_ExternalMesh_getScale(resc,resv,argc,(mxArray**)(argv)); break; - case 1033: flag=_wrap_ExternalMesh_setScale(resc,resv,argc,(mxArray**)(argv)); break; - case 1034: flag=_wrap_new_ExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; - case 1035: flag=_wrap_delete_ModelSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; - case 1036: flag=_wrap_new_ModelSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; - case 1037: flag=_wrap_ModelSolidShapes_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 1038: flag=_wrap_ModelSolidShapes_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1039: flag=_wrap_ModelSolidShapes_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1040: flag=_wrap_ModelSolidShapes_getLinkSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; - case 1041: flag=_wrap_Neighbor_neighborLink_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1042: flag=_wrap_Neighbor_neighborLink_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1043: flag=_wrap_Neighbor_neighborJoint_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1044: flag=_wrap_Neighbor_neighborJoint_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1045: flag=_wrap_new_Neighbor(resc,resv,argc,(mxArray**)(argv)); break; - case 1046: flag=_wrap_delete_Neighbor(resc,resv,argc,(mxArray**)(argv)); break; - case 1047: flag=_wrap_new_Model(resc,resv,argc,(mxArray**)(argv)); break; - case 1048: flag=_wrap_Model_copy(resc,resv,argc,(mxArray**)(argv)); break; - case 1049: flag=_wrap_delete_Model(resc,resv,argc,(mxArray**)(argv)); break; - case 1050: flag=_wrap_Model_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1051: flag=_wrap_Model_getLinkName(resc,resv,argc,(mxArray**)(argv)); break; - case 1052: flag=_wrap_Model_getLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1053: flag=_wrap_Model_isValidLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1054: flag=_wrap_Model_getLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1055: flag=_wrap_Model_addLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1056: flag=_wrap_Model_getNrOfJoints(resc,resv,argc,(mxArray**)(argv)); break; - case 1057: flag=_wrap_Model_getJointName(resc,resv,argc,(mxArray**)(argv)); break; - case 1058: flag=_wrap_Model_getTotalMass(resc,resv,argc,(mxArray**)(argv)); break; - case 1059: flag=_wrap_Model_getJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1060: flag=_wrap_Model_getJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1061: flag=_wrap_Model_isValidJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1062: flag=_wrap_Model_isLinkNameUsed(resc,resv,argc,(mxArray**)(argv)); break; - case 1063: flag=_wrap_Model_isJointNameUsed(resc,resv,argc,(mxArray**)(argv)); break; - case 1064: flag=_wrap_Model_isFrameNameUsed(resc,resv,argc,(mxArray**)(argv)); break; - case 1065: flag=_wrap_Model_addJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1066: flag=_wrap_Model_addJointAndLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1067: flag=_wrap_Model_insertLinkToExistingJointAndAddJointForDisplacedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1068: flag=_wrap_Model_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 1069: flag=_wrap_Model_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1070: flag=_wrap_Model_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; - case 1071: flag=_wrap_Model_addAdditionalFrameToLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1072: flag=_wrap_Model_getFrameName(resc,resv,argc,(mxArray**)(argv)); break; - case 1073: flag=_wrap_Model_getFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1074: flag=_wrap_Model_isValidFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1075: flag=_wrap_Model_getFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1076: flag=_wrap_Model_getFrameLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1077: flag=_wrap_Model_getLinkAdditionalFrames(resc,resv,argc,(mxArray**)(argv)); break; - case 1078: flag=_wrap_Model_getNrOfNeighbors(resc,resv,argc,(mxArray**)(argv)); break; - case 1079: flag=_wrap_Model_getNeighbor(resc,resv,argc,(mxArray**)(argv)); break; - case 1080: flag=_wrap_Model_setDefaultBaseLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1081: flag=_wrap_Model_getDefaultBaseLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1082: flag=_wrap_Model_computeFullTreeTraversal(resc,resv,argc,(mxArray**)(argv)); break; - case 1083: flag=_wrap_Model_getInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1084: flag=_wrap_Model_updateInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1085: flag=_wrap_Model_visualSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; - case 1086: flag=_wrap_Model_collisionSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; - case 1087: flag=_wrap_Model_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 1088: flag=_wrap_new_JointPosDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1089: flag=_wrap_JointPosDoubleArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1090: flag=_wrap_JointPosDoubleArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1091: flag=_wrap_delete_JointPosDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1092: flag=_wrap_new_JointDOFsDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1093: flag=_wrap_JointDOFsDoubleArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1094: flag=_wrap_JointDOFsDoubleArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1095: flag=_wrap_delete_JointDOFsDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1096: flag=_wrap_new_DOFSpatialForceArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1097: flag=_wrap_DOFSpatialForceArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1098: flag=_wrap_DOFSpatialForceArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1099: flag=_wrap_DOFSpatialForceArray_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 1100: flag=_wrap_delete_DOFSpatialForceArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1101: flag=_wrap_new_DOFSpatialMotionArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1102: flag=_wrap_DOFSpatialMotionArray_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1103: flag=_wrap_DOFSpatialMotionArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1104: flag=_wrap_DOFSpatialMotionArray_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 1105: flag=_wrap_delete_DOFSpatialMotionArray(resc,resv,argc,(mxArray**)(argv)); break; - case 1106: flag=_wrap_new_FrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1107: flag=_wrap_FrameFreeFloatingJacobian_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1108: flag=_wrap_FrameFreeFloatingJacobian_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1109: flag=_wrap_delete_FrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1110: flag=_wrap_new_MomentumFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1111: flag=_wrap_MomentumFreeFloatingJacobian_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1112: flag=_wrap_MomentumFreeFloatingJacobian_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1113: flag=_wrap_delete_MomentumFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1114: flag=_wrap_new_FreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1115: flag=_wrap_FreeFloatingMassMatrix_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1116: flag=_wrap_delete_FreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1117: flag=_wrap_new_FreeFloatingPos(resc,resv,argc,(mxArray**)(argv)); break; - case 1118: flag=_wrap_FreeFloatingPos_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1119: flag=_wrap_FreeFloatingPos_worldBasePos(resc,resv,argc,(mxArray**)(argv)); break; - case 1120: flag=_wrap_FreeFloatingPos_jointPos(resc,resv,argc,(mxArray**)(argv)); break; - case 1121: flag=_wrap_FreeFloatingPos_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; - case 1122: flag=_wrap_delete_FreeFloatingPos(resc,resv,argc,(mxArray**)(argv)); break; - case 1123: flag=_wrap_new_FreeFloatingGeneralizedTorques(resc,resv,argc,(mxArray**)(argv)); break; - case 1124: flag=_wrap_FreeFloatingGeneralizedTorques_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1125: flag=_wrap_FreeFloatingGeneralizedTorques_baseWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1126: flag=_wrap_FreeFloatingGeneralizedTorques_jointTorques(resc,resv,argc,(mxArray**)(argv)); break; - case 1127: flag=_wrap_FreeFloatingGeneralizedTorques_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1128: flag=_wrap_delete_FreeFloatingGeneralizedTorques(resc,resv,argc,(mxArray**)(argv)); break; - case 1129: flag=_wrap_new_FreeFloatingVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1130: flag=_wrap_FreeFloatingVel_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1131: flag=_wrap_FreeFloatingVel_baseVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1132: flag=_wrap_FreeFloatingVel_jointVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1133: flag=_wrap_FreeFloatingVel_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1134: flag=_wrap_delete_FreeFloatingVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1135: flag=_wrap_new_FreeFloatingAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1136: flag=_wrap_FreeFloatingAcc_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1137: flag=_wrap_FreeFloatingAcc_baseAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1138: flag=_wrap_FreeFloatingAcc_jointAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1139: flag=_wrap_FreeFloatingAcc_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1140: flag=_wrap_delete_FreeFloatingAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1141: flag=_wrap_ContactWrench_contactId(resc,resv,argc,(mxArray**)(argv)); break; - case 1142: flag=_wrap_ContactWrench_contactPoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1143: flag=_wrap_ContactWrench_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1144: flag=_wrap_new_ContactWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1145: flag=_wrap_delete_ContactWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1146: flag=_wrap_new_LinkContactWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 1147: flag=_wrap_LinkContactWrenches_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1148: flag=_wrap_LinkContactWrenches_getNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1149: flag=_wrap_LinkContactWrenches_setNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1150: flag=_wrap_LinkContactWrenches_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1151: flag=_wrap_LinkContactWrenches_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1152: flag=_wrap_LinkContactWrenches_computeNetWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 1153: flag=_wrap_LinkContactWrenches_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 1154: flag=_wrap_delete_LinkContactWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 1155: flag=_wrap_getRandomLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1156: flag=_wrap_addRandomLinkToModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1157: flag=_wrap_addRandomAdditionalFrameToModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1158: flag=_wrap_getRandomLinkIndexOfModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1159: flag=_wrap_getRandomLinkOfModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1160: flag=_wrap_int2string(resc,resv,argc,(mxArray**)(argv)); break; - case 1161: flag=_wrap_getRandomModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1162: flag=_wrap_getRandomChain(resc,resv,argc,(mxArray**)(argv)); break; - case 1163: flag=_wrap_getRandomJointPositions(resc,resv,argc,(mxArray**)(argv)); break; - case 1164: flag=_wrap_getRandomInverseDynamicsInputs(resc,resv,argc,(mxArray**)(argv)); break; - case 1165: flag=_wrap_removeFakeLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1166: flag=_wrap_createReducedModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1167: flag=_wrap_createModelWithNormalizedJointNumbering(resc,resv,argc,(mxArray**)(argv)); break; - case 1168: flag=_wrap_extractSubModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1169: flag=_wrap_new_SubModelDecomposition(resc,resv,argc,(mxArray**)(argv)); break; - case 1170: flag=_wrap_delete_SubModelDecomposition(resc,resv,argc,(mxArray**)(argv)); break; - case 1171: flag=_wrap_SubModelDecomposition_splitModelAlongJoints(resc,resv,argc,(mxArray**)(argv)); break; - case 1172: flag=_wrap_SubModelDecomposition_setNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; - case 1173: flag=_wrap_SubModelDecomposition_getNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; - case 1174: flag=_wrap_SubModelDecomposition_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1175: flag=_wrap_SubModelDecomposition_getTraversal(resc,resv,argc,(mxArray**)(argv)); break; - case 1176: flag=_wrap_SubModelDecomposition_getSubModelOfLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1177: flag=_wrap_SubModelDecomposition_getSubModelOfFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1178: flag=_wrap_computeTransformToTraversalBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1179: flag=_wrap_computeTransformToSubModelBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1180: flag=_wrap_SolidShapesVector_pop(resc,resv,argc,(mxArray**)(argv)); break; - case 1181: flag=_wrap_SolidShapesVector_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 1182: flag=_wrap_SolidShapesVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; - case 1183: flag=_wrap_SolidShapesVector_append(resc,resv,argc,(mxArray**)(argv)); break; - case 1184: flag=_wrap_SolidShapesVector_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 1185: flag=_wrap_SolidShapesVector_size(resc,resv,argc,(mxArray**)(argv)); break; - case 1186: flag=_wrap_SolidShapesVector_swap(resc,resv,argc,(mxArray**)(argv)); break; - case 1187: flag=_wrap_SolidShapesVector_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 1188: flag=_wrap_SolidShapesVector_end(resc,resv,argc,(mxArray**)(argv)); break; - case 1189: flag=_wrap_SolidShapesVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 1190: flag=_wrap_SolidShapesVector_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 1191: flag=_wrap_SolidShapesVector_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 1192: flag=_wrap_SolidShapesVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; - case 1193: flag=_wrap_SolidShapesVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1194: flag=_wrap_SolidShapesVector_erase(resc,resv,argc,(mxArray**)(argv)); break; - case 1195: flag=_wrap_new_SolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1196: flag=_wrap_SolidShapesVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1197: flag=_wrap_SolidShapesVector_front(resc,resv,argc,(mxArray**)(argv)); break; - case 1198: flag=_wrap_SolidShapesVector_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1199: flag=_wrap_SolidShapesVector_assign(resc,resv,argc,(mxArray**)(argv)); break; - case 1200: flag=_wrap_SolidShapesVector_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1201: flag=_wrap_SolidShapesVector_insert(resc,resv,argc,(mxArray**)(argv)); break; - case 1202: flag=_wrap_SolidShapesVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 1203: flag=_wrap_SolidShapesVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 1204: flag=_wrap_delete_SolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1205: flag=_wrap_LinksSolidShapesVector_pop(resc,resv,argc,(mxArray**)(argv)); break; - case 1206: flag=_wrap_LinksSolidShapesVector_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 1207: flag=_wrap_LinksSolidShapesVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; - case 1208: flag=_wrap_LinksSolidShapesVector_append(resc,resv,argc,(mxArray**)(argv)); break; - case 1209: flag=_wrap_LinksSolidShapesVector_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 1210: flag=_wrap_LinksSolidShapesVector_size(resc,resv,argc,(mxArray**)(argv)); break; - case 1211: flag=_wrap_LinksSolidShapesVector_swap(resc,resv,argc,(mxArray**)(argv)); break; - case 1212: flag=_wrap_LinksSolidShapesVector_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 1213: flag=_wrap_LinksSolidShapesVector_end(resc,resv,argc,(mxArray**)(argv)); break; - case 1214: flag=_wrap_LinksSolidShapesVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 1215: flag=_wrap_LinksSolidShapesVector_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 1216: flag=_wrap_LinksSolidShapesVector_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 1217: flag=_wrap_LinksSolidShapesVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; - case 1218: flag=_wrap_LinksSolidShapesVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1219: flag=_wrap_LinksSolidShapesVector_erase(resc,resv,argc,(mxArray**)(argv)); break; - case 1220: flag=_wrap_new_LinksSolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1221: flag=_wrap_LinksSolidShapesVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1222: flag=_wrap_LinksSolidShapesVector_front(resc,resv,argc,(mxArray**)(argv)); break; - case 1223: flag=_wrap_LinksSolidShapesVector_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1224: flag=_wrap_LinksSolidShapesVector_assign(resc,resv,argc,(mxArray**)(argv)); break; - case 1225: flag=_wrap_LinksSolidShapesVector_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1226: flag=_wrap_LinksSolidShapesVector_insert(resc,resv,argc,(mxArray**)(argv)); break; - case 1227: flag=_wrap_LinksSolidShapesVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 1228: flag=_wrap_LinksSolidShapesVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 1229: flag=_wrap_delete_LinksSolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1230: flag=_wrap_ForwardPositionKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1231: flag=_wrap_ForwardVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1232: flag=_wrap_ForwardPosVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1233: flag=_wrap_ForwardPosVelKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1234: flag=_wrap_ForwardAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1235: flag=_wrap_ForwardBiasAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1236: flag=_wrap_ComputeLinearAndAngularMomentum(resc,resv,argc,(mxArray**)(argv)); break; - case 1237: flag=_wrap_ComputeLinearAndAngularMomentumDerivativeBias(resc,resv,argc,(mxArray**)(argv)); break; - case 1238: flag=_wrap_RNEADynamicPhase(resc,resv,argc,(mxArray**)(argv)); break; - case 1239: flag=_wrap_CompositeRigidBodyAlgorithm(resc,resv,argc,(mxArray**)(argv)); break; - case 1240: flag=_wrap_new_ArticulatedBodyAlgorithmInternalBuffers(resc,resv,argc,(mxArray**)(argv)); break; - case 1241: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1242: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1243: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_S_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1244: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_S_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1245: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_U_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1246: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_U_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1247: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_D_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1248: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_D_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1249: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_u_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1250: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_u_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1251: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1252: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1253: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1254: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1255: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1256: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1257: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1258: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1259: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1260: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1261: flag=_wrap_delete_ArticulatedBodyAlgorithmInternalBuffers(resc,resv,argc,(mxArray**)(argv)); break; - case 1262: flag=_wrap_ArticulatedBodyAlgorithm(resc,resv,argc,(mxArray**)(argv)); break; - case 1263: flag=_wrap_InverseDynamicsInertialParametersRegressor(resc,resv,argc,(mxArray**)(argv)); break; - case 1264: flag=_wrap_DHLink_A_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1265: flag=_wrap_DHLink_A_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1266: flag=_wrap_DHLink_D_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1267: flag=_wrap_DHLink_D_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1268: flag=_wrap_DHLink_Alpha_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1269: flag=_wrap_DHLink_Alpha_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1270: flag=_wrap_DHLink_Offset_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1271: flag=_wrap_DHLink_Offset_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1272: flag=_wrap_DHLink_Min_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1273: flag=_wrap_DHLink_Min_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1274: flag=_wrap_DHLink_Max_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1275: flag=_wrap_DHLink_Max_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1276: flag=_wrap_new_DHLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1277: flag=_wrap_delete_DHLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1278: flag=_wrap_DHChain_setNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1279: flag=_wrap_DHChain_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1280: flag=_wrap_DHChain_setH0(resc,resv,argc,(mxArray**)(argv)); break; - case 1281: flag=_wrap_DHChain_getH0(resc,resv,argc,(mxArray**)(argv)); break; - case 1282: flag=_wrap_DHChain_setHN(resc,resv,argc,(mxArray**)(argv)); break; - case 1283: flag=_wrap_DHChain_getHN(resc,resv,argc,(mxArray**)(argv)); break; - case 1284: flag=_wrap_DHChain_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 1285: flag=_wrap_DHChain_getDOFName(resc,resv,argc,(mxArray**)(argv)); break; - case 1286: flag=_wrap_DHChain_setDOFName(resc,resv,argc,(mxArray**)(argv)); break; - case 1287: flag=_wrap_DHChain_toModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1288: flag=_wrap_DHChain_fromModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1289: flag=_wrap_new_DHChain(resc,resv,argc,(mxArray**)(argv)); break; - case 1290: flag=_wrap_delete_DHChain(resc,resv,argc,(mxArray**)(argv)); break; - case 1291: flag=_wrap_TransformFromDHCraig1989(resc,resv,argc,(mxArray**)(argv)); break; - case 1292: flag=_wrap_TransformFromDH(resc,resv,argc,(mxArray**)(argv)); break; - case 1293: flag=_wrap_ExtractDHChainFromModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1294: flag=_wrap_CreateModelFromDHChain(resc,resv,argc,(mxArray**)(argv)); break; - case 1295: flag=_wrap_NR_OF_SENSOR_TYPES_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1296: flag=_wrap_isLinkSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1297: flag=_wrap_isJointSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1298: flag=_wrap_getSensorTypeSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1299: flag=_wrap_delete_Sensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1300: flag=_wrap_Sensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1301: flag=_wrap_Sensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1302: flag=_wrap_Sensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1303: flag=_wrap_Sensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1304: flag=_wrap_Sensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1305: flag=_wrap_Sensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1306: flag=_wrap_Sensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1307: flag=_wrap_delete_JointSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1308: flag=_wrap_JointSensor_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1309: flag=_wrap_JointSensor_getParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1310: flag=_wrap_JointSensor_setParentJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1311: flag=_wrap_JointSensor_setParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1312: flag=_wrap_JointSensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1313: flag=_wrap_delete_LinkSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1314: flag=_wrap_LinkSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1315: flag=_wrap_LinkSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1316: flag=_wrap_LinkSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1317: flag=_wrap_LinkSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1318: flag=_wrap_LinkSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1319: flag=_wrap_LinkSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1320: flag=_wrap_LinkSensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1321: flag=_wrap_new_SensorsList(resc,resv,argc,(mxArray**)(argv)); break; - case 1322: flag=_wrap_delete_SensorsList(resc,resv,argc,(mxArray**)(argv)); break; - case 1323: flag=_wrap_SensorsList_addSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1324: flag=_wrap_SensorsList_setSerialization(resc,resv,argc,(mxArray**)(argv)); break; - case 1325: flag=_wrap_SensorsList_getSerialization(resc,resv,argc,(mxArray**)(argv)); break; - case 1326: flag=_wrap_SensorsList_getNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1327: flag=_wrap_SensorsList_getSensorIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1328: flag=_wrap_SensorsList_getSizeOfAllSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1329: flag=_wrap_SensorsList_getSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1330: flag=_wrap_SensorsList_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1331: flag=_wrap_SensorsList_removeSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1332: flag=_wrap_SensorsList_removeAllSensorsOfType(resc,resv,argc,(mxArray**)(argv)); break; - case 1333: flag=_wrap_SensorsList_getSixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1334: flag=_wrap_SensorsList_getAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1335: flag=_wrap_SensorsList_getGyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1336: flag=_wrap_SensorsList_getThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1337: flag=_wrap_SensorsList_getThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1338: flag=_wrap_new_SensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1339: flag=_wrap_delete_SensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1340: flag=_wrap_SensorsMeasurements_setNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1341: flag=_wrap_SensorsMeasurements_getNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1342: flag=_wrap_SensorsMeasurements_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1343: flag=_wrap_SensorsMeasurements_toVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1344: flag=_wrap_SensorsMeasurements_setMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1345: flag=_wrap_SensorsMeasurements_getMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1346: flag=_wrap_SensorsMeasurements_getSizeOfAllSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1347: flag=_wrap_new_SixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1348: flag=_wrap_delete_SixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1349: flag=_wrap_SixAxisForceTorqueSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1350: flag=_wrap_SixAxisForceTorqueSensor_setFirstLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1351: flag=_wrap_SixAxisForceTorqueSensor_setSecondLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1352: flag=_wrap_SixAxisForceTorqueSensor_getFirstLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1353: flag=_wrap_SixAxisForceTorqueSensor_getSecondLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1354: flag=_wrap_SixAxisForceTorqueSensor_setFirstLinkName(resc,resv,argc,(mxArray**)(argv)); break; - case 1355: flag=_wrap_SixAxisForceTorqueSensor_setSecondLinkName(resc,resv,argc,(mxArray**)(argv)); break; - case 1356: flag=_wrap_SixAxisForceTorqueSensor_getFirstLinkName(resc,resv,argc,(mxArray**)(argv)); break; - case 1357: flag=_wrap_SixAxisForceTorqueSensor_getSecondLinkName(resc,resv,argc,(mxArray**)(argv)); break; - case 1358: flag=_wrap_SixAxisForceTorqueSensor_setParentJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1359: flag=_wrap_SixAxisForceTorqueSensor_setParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1360: flag=_wrap_SixAxisForceTorqueSensor_setAppliedWrenchLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1361: flag=_wrap_SixAxisForceTorqueSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1362: flag=_wrap_SixAxisForceTorqueSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1363: flag=_wrap_SixAxisForceTorqueSensor_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; - case 1364: flag=_wrap_SixAxisForceTorqueSensor_getParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1365: flag=_wrap_SixAxisForceTorqueSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1366: flag=_wrap_SixAxisForceTorqueSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1367: flag=_wrap_SixAxisForceTorqueSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1368: flag=_wrap_SixAxisForceTorqueSensor_getAppliedWrenchLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1369: flag=_wrap_SixAxisForceTorqueSensor_isLinkAttachedToSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1370: flag=_wrap_SixAxisForceTorqueSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1371: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1372: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1373: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1374: flag=_wrap_SixAxisForceTorqueSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1375: flag=_wrap_SixAxisForceTorqueSensor_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 1376: flag=_wrap_new_AccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1377: flag=_wrap_delete_AccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1378: flag=_wrap_AccelerometerSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1379: flag=_wrap_AccelerometerSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1380: flag=_wrap_AccelerometerSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1381: flag=_wrap_AccelerometerSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1382: flag=_wrap_AccelerometerSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1383: flag=_wrap_AccelerometerSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1384: flag=_wrap_AccelerometerSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1385: flag=_wrap_AccelerometerSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1386: flag=_wrap_AccelerometerSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1387: flag=_wrap_AccelerometerSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1388: flag=_wrap_AccelerometerSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1389: flag=_wrap_AccelerometerSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1390: flag=_wrap_AccelerometerSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1391: flag=_wrap_new_GyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1392: flag=_wrap_delete_GyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1393: flag=_wrap_GyroscopeSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1394: flag=_wrap_GyroscopeSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1395: flag=_wrap_GyroscopeSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1396: flag=_wrap_GyroscopeSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1397: flag=_wrap_GyroscopeSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1398: flag=_wrap_GyroscopeSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1399: flag=_wrap_GyroscopeSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1400: flag=_wrap_GyroscopeSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1401: flag=_wrap_GyroscopeSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1402: flag=_wrap_GyroscopeSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1403: flag=_wrap_GyroscopeSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1404: flag=_wrap_GyroscopeSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1405: flag=_wrap_GyroscopeSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1406: flag=_wrap_new_ThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1407: flag=_wrap_delete_ThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1408: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1409: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1410: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1411: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1412: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1413: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1414: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1415: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1416: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1417: flag=_wrap_ThreeAxisAngularAccelerometerSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1418: flag=_wrap_ThreeAxisAngularAccelerometerSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1419: flag=_wrap_ThreeAxisAngularAccelerometerSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1420: flag=_wrap_ThreeAxisAngularAccelerometerSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; - case 1421: flag=_wrap_new_ThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1422: flag=_wrap_delete_ThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1423: flag=_wrap_ThreeAxisForceTorqueContactSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; - case 1424: flag=_wrap_ThreeAxisForceTorqueContactSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1425: flag=_wrap_ThreeAxisForceTorqueContactSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1426: flag=_wrap_ThreeAxisForceTorqueContactSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1427: flag=_wrap_ThreeAxisForceTorqueContactSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1428: flag=_wrap_ThreeAxisForceTorqueContactSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; - case 1429: flag=_wrap_ThreeAxisForceTorqueContactSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1430: flag=_wrap_ThreeAxisForceTorqueContactSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1431: flag=_wrap_ThreeAxisForceTorqueContactSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1432: flag=_wrap_ThreeAxisForceTorqueContactSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1433: flag=_wrap_ThreeAxisForceTorqueContactSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; - case 1434: flag=_wrap_ThreeAxisForceTorqueContactSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; - case 1435: flag=_wrap_ThreeAxisForceTorqueContactSensor_setLoadCellLocations(resc,resv,argc,(mxArray**)(argv)); break; - case 1436: flag=_wrap_ThreeAxisForceTorqueContactSensor_getLoadCellLocations(resc,resv,argc,(mxArray**)(argv)); break; - case 1437: flag=_wrap_ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1438: flag=_wrap_ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1439: flag=_wrap_predictSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1440: flag=_wrap_predictSensorsMeasurementsFromRawBuffers(resc,resv,argc,(mxArray**)(argv)); break; - case 1441: flag=_wrap_dofsListFromURDF(resc,resv,argc,(mxArray**)(argv)); break; - case 1442: flag=_wrap_dofsListFromURDFString(resc,resv,argc,(mxArray**)(argv)); break; - case 1443: flag=_wrap_ModelParserOptions_addSensorFramesAsAdditionalFrames_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1444: flag=_wrap_ModelParserOptions_addSensorFramesAsAdditionalFrames_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1445: flag=_wrap_ModelParserOptions_originalFilename_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1446: flag=_wrap_ModelParserOptions_originalFilename_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1447: flag=_wrap_new_ModelParserOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1448: flag=_wrap_delete_ModelParserOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1449: flag=_wrap_new_ModelLoader(resc,resv,argc,(mxArray**)(argv)); break; - case 1450: flag=_wrap_delete_ModelLoader(resc,resv,argc,(mxArray**)(argv)); break; - case 1451: flag=_wrap_ModelLoader_parsingOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1452: flag=_wrap_ModelLoader_setParsingOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1453: flag=_wrap_ModelLoader_loadModelFromString(resc,resv,argc,(mxArray**)(argv)); break; - case 1454: flag=_wrap_ModelLoader_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1455: flag=_wrap_ModelLoader_loadReducedModelFromFullModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1456: flag=_wrap_ModelLoader_loadReducedModelFromString(resc,resv,argc,(mxArray**)(argv)); break; - case 1457: flag=_wrap_ModelLoader_loadReducedModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1458: flag=_wrap_ModelLoader_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1459: flag=_wrap_ModelLoader_sensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1460: flag=_wrap_ModelLoader_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1461: flag=_wrap_ModelExporterOptions_baseLink_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1462: flag=_wrap_ModelExporterOptions_baseLink_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1463: flag=_wrap_ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1464: flag=_wrap_ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1465: flag=_wrap_ModelExporterOptions_robotExportedName_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1466: flag=_wrap_ModelExporterOptions_robotExportedName_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1467: flag=_wrap_new_ModelExporterOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1468: flag=_wrap_delete_ModelExporterOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1469: flag=_wrap_new_ModelExporter(resc,resv,argc,(mxArray**)(argv)); break; - case 1470: flag=_wrap_delete_ModelExporter(resc,resv,argc,(mxArray**)(argv)); break; - case 1471: flag=_wrap_ModelExporter_exportingOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1472: flag=_wrap_ModelExporter_setExportingOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1473: flag=_wrap_ModelExporter_init(resc,resv,argc,(mxArray**)(argv)); break; - case 1474: flag=_wrap_ModelExporter_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1475: flag=_wrap_ModelExporter_sensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1476: flag=_wrap_ModelExporter_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1477: flag=_wrap_ModelExporter_exportModelToString(resc,resv,argc,(mxArray**)(argv)); break; - case 1478: flag=_wrap_ModelExporter_exportModelToFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1479: flag=_wrap_new_ModelCalibrationHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 1480: flag=_wrap_delete_ModelCalibrationHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 1481: flag=_wrap_ModelCalibrationHelper_loadModelFromString(resc,resv,argc,(mxArray**)(argv)); break; - case 1482: flag=_wrap_ModelCalibrationHelper_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1483: flag=_wrap_ModelCalibrationHelper_updateModelInertialParametersToString(resc,resv,argc,(mxArray**)(argv)); break; - case 1484: flag=_wrap_ModelCalibrationHelper_updateModelInertialParametersToFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1485: flag=_wrap_ModelCalibrationHelper_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1486: flag=_wrap_ModelCalibrationHelper_sensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1487: flag=_wrap_ModelCalibrationHelper_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1488: flag=_wrap_new_UnknownWrenchContact(resc,resv,argc,(mxArray**)(argv)); break; - case 1489: flag=_wrap_UnknownWrenchContact_unknownType_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1490: flag=_wrap_UnknownWrenchContact_unknownType_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1491: flag=_wrap_UnknownWrenchContact_contactPoint_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1492: flag=_wrap_UnknownWrenchContact_contactPoint_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1493: flag=_wrap_UnknownWrenchContact_forceDirection_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1494: flag=_wrap_UnknownWrenchContact_forceDirection_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1495: flag=_wrap_UnknownWrenchContact_knownWrench_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1496: flag=_wrap_UnknownWrenchContact_knownWrench_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1497: flag=_wrap_UnknownWrenchContact_contactId_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1498: flag=_wrap_UnknownWrenchContact_contactId_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1499: flag=_wrap_delete_UnknownWrenchContact(resc,resv,argc,(mxArray**)(argv)); break; - case 1500: flag=_wrap_new_LinkUnknownWrenchContacts(resc,resv,argc,(mxArray**)(argv)); break; - case 1501: flag=_wrap_LinkUnknownWrenchContacts_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 1502: flag=_wrap_LinkUnknownWrenchContacts_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1503: flag=_wrap_LinkUnknownWrenchContacts_getNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1504: flag=_wrap_LinkUnknownWrenchContacts_setNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1505: flag=_wrap_LinkUnknownWrenchContacts_addNewContactForLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1506: flag=_wrap_LinkUnknownWrenchContacts_addNewContactInFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1507: flag=_wrap_LinkUnknownWrenchContacts_addNewUnknownFullWrenchInFrameOrigin(resc,resv,argc,(mxArray**)(argv)); break; - case 1508: flag=_wrap_LinkUnknownWrenchContacts_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; - case 1509: flag=_wrap_LinkUnknownWrenchContacts_toString(resc,resv,argc,(mxArray**)(argv)); break; - case 1510: flag=_wrap_delete_LinkUnknownWrenchContacts(resc,resv,argc,(mxArray**)(argv)); break; - case 1511: flag=_wrap_new_estimateExternalWrenchesBuffers(resc,resv,argc,(mxArray**)(argv)); break; - case 1512: flag=_wrap_estimateExternalWrenchesBuffers_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1513: flag=_wrap_estimateExternalWrenchesBuffers_getNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; - case 1514: flag=_wrap_estimateExternalWrenchesBuffers_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1515: flag=_wrap_estimateExternalWrenchesBuffers_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; - case 1516: flag=_wrap_estimateExternalWrenchesBuffers_A_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1517: flag=_wrap_estimateExternalWrenchesBuffers_A_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1518: flag=_wrap_estimateExternalWrenchesBuffers_x_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1519: flag=_wrap_estimateExternalWrenchesBuffers_x_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1520: flag=_wrap_estimateExternalWrenchesBuffers_b_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1521: flag=_wrap_estimateExternalWrenchesBuffers_b_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1522: flag=_wrap_estimateExternalWrenchesBuffers_b_contacts_subtree_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1523: flag=_wrap_estimateExternalWrenchesBuffers_b_contacts_subtree_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1524: flag=_wrap_estimateExternalWrenchesBuffers_subModelBase_H_link_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1525: flag=_wrap_estimateExternalWrenchesBuffers_subModelBase_H_link_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1526: flag=_wrap_delete_estimateExternalWrenchesBuffers(resc,resv,argc,(mxArray**)(argv)); break; - case 1527: flag=_wrap_estimateExternalWrenchesWithoutInternalFT(resc,resv,argc,(mxArray**)(argv)); break; - case 1528: flag=_wrap_estimateExternalWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 1529: flag=_wrap_dynamicsEstimationForwardVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1530: flag=_wrap_dynamicsEstimationForwardVelKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1531: flag=_wrap_computeLinkNetWrenchesWithoutGravity(resc,resv,argc,(mxArray**)(argv)); break; - case 1532: flag=_wrap_estimateLinkContactWrenchesFromLinkNetExternalWrenches(resc,resv,argc,(mxArray**)(argv)); break; - case 1533: flag=_wrap_new_ExtWrenchesAndJointTorquesEstimator(resc,resv,argc,(mxArray**)(argv)); break; - case 1534: flag=_wrap_delete_ExtWrenchesAndJointTorquesEstimator(resc,resv,argc,(mxArray**)(argv)); break; - case 1535: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_setModelAndSensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1536: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1537: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFileWithSpecifiedDOFs(resc,resv,argc,(mxArray**)(argv)); break; - case 1538: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1539: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_sensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1540: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_submodels(resc,resv,argc,(mxArray**)(argv)); break; - case 1541: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1542: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1543: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_computeExpectedFTSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1544: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_estimateExtWrenchesAndJointTorques(resc,resv,argc,(mxArray**)(argv)); break; - case 1545: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_checkThatTheModelIsStill(resc,resv,argc,(mxArray**)(argv)); break; - case 1546: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_estimateLinkNetWrenchesWithoutGravity(resc,resv,argc,(mxArray**)(argv)); break; - case 1547: flag=_wrap_new_SimpleLeggedOdometry(resc,resv,argc,(mxArray**)(argv)); break; - case 1548: flag=_wrap_delete_SimpleLeggedOdometry(resc,resv,argc,(mxArray**)(argv)); break; - case 1549: flag=_wrap_SimpleLeggedOdometry_setModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1550: flag=_wrap_SimpleLeggedOdometry_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1551: flag=_wrap_SimpleLeggedOdometry_updateKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 1552: flag=_wrap_SimpleLeggedOdometry_init(resc,resv,argc,(mxArray**)(argv)); break; - case 1553: flag=_wrap_SimpleLeggedOdometry_changeFixedFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1554: flag=_wrap_SimpleLeggedOdometry_getCurrentFixedLink(resc,resv,argc,(mxArray**)(argv)); break; - case 1555: flag=_wrap_SimpleLeggedOdometry_getWorldLinkTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1556: flag=_wrap_SimpleLeggedOdometry_getWorldFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1557: flag=_wrap_isLinkBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1558: flag=_wrap_isJointBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1559: flag=_wrap_isDOFBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1560: flag=_wrap_new_BerdyOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1561: flag=_wrap_BerdyOptions_berdyVariant_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1562: flag=_wrap_BerdyOptions_berdyVariant_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1563: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1564: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1565: flag=_wrap_BerdyOptions_includeAllJointAccelerationsAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1566: flag=_wrap_BerdyOptions_includeAllJointAccelerationsAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1567: flag=_wrap_BerdyOptions_includeAllJointTorquesAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1568: flag=_wrap_BerdyOptions_includeAllJointTorquesAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1569: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1570: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1571: flag=_wrap_BerdyOptions_includeFixedBaseExternalWrench_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1572: flag=_wrap_BerdyOptions_includeFixedBaseExternalWrench_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1573: flag=_wrap_BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1574: flag=_wrap_BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1575: flag=_wrap_BerdyOptions_baseLink_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1576: flag=_wrap_BerdyOptions_baseLink_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1577: flag=_wrap_BerdyOptions_checkConsistency(resc,resv,argc,(mxArray**)(argv)); break; - case 1578: flag=_wrap_delete_BerdyOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1579: flag=_wrap_BerdySensor_type_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1580: flag=_wrap_BerdySensor_type_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1581: flag=_wrap_BerdySensor_id_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1582: flag=_wrap_BerdySensor_id_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1583: flag=_wrap_BerdySensor_range_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1584: flag=_wrap_BerdySensor_range_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1585: flag=_wrap_BerdySensor_eq(resc,resv,argc,(mxArray**)(argv)); break; - case 1586: flag=_wrap_BerdySensor_lt(resc,resv,argc,(mxArray**)(argv)); break; - case 1587: flag=_wrap_new_BerdySensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1588: flag=_wrap_delete_BerdySensor(resc,resv,argc,(mxArray**)(argv)); break; - case 1589: flag=_wrap_BerdyDynamicVariable_type_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1590: flag=_wrap_BerdyDynamicVariable_type_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1591: flag=_wrap_BerdyDynamicVariable_id_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1592: flag=_wrap_BerdyDynamicVariable_id_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1593: flag=_wrap_BerdyDynamicVariable_range_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1594: flag=_wrap_BerdyDynamicVariable_range_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1595: flag=_wrap_BerdyDynamicVariable_eq(resc,resv,argc,(mxArray**)(argv)); break; - case 1596: flag=_wrap_BerdyDynamicVariable_lt(resc,resv,argc,(mxArray**)(argv)); break; - case 1597: flag=_wrap_new_BerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1598: flag=_wrap_delete_BerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1599: flag=_wrap_new_BerdyHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 1600: flag=_wrap_BerdyHelper_dynamicTraversal(resc,resv,argc,(mxArray**)(argv)); break; - case 1601: flag=_wrap_BerdyHelper_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1602: flag=_wrap_BerdyHelper_sensors(resc,resv,argc,(mxArray**)(argv)); break; - case 1603: flag=_wrap_BerdyHelper_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1604: flag=_wrap_BerdyHelper_init(resc,resv,argc,(mxArray**)(argv)); break; - case 1605: flag=_wrap_BerdyHelper_getOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1606: flag=_wrap_BerdyHelper_getNrOfDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 1607: flag=_wrap_BerdyHelper_getNrOfDynamicEquations(resc,resv,argc,(mxArray**)(argv)); break; - case 1608: flag=_wrap_BerdyHelper_getNrOfSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1609: flag=_wrap_BerdyHelper_resizeAndZeroBerdyMatrices(resc,resv,argc,(mxArray**)(argv)); break; - case 1610: flag=_wrap_BerdyHelper_getBerdyMatrices(resc,resv,argc,(mxArray**)(argv)); break; - case 1611: flag=_wrap_BerdyHelper_getSensorsOrdering(resc,resv,argc,(mxArray**)(argv)); break; - case 1612: flag=_wrap_BerdyHelper_getRangeSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1613: flag=_wrap_BerdyHelper_getRangeDOFSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1614: flag=_wrap_BerdyHelper_getRangeJointSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1615: flag=_wrap_BerdyHelper_getRangeLinkSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1616: flag=_wrap_BerdyHelper_getRangeRCMSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1617: flag=_wrap_BerdyHelper_getRangeLinkVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1618: flag=_wrap_BerdyHelper_getRangeJointVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1619: flag=_wrap_BerdyHelper_getRangeDOFVariable(resc,resv,argc,(mxArray**)(argv)); break; - case 1620: flag=_wrap_BerdyHelper_getDynamicVariablesOrdering(resc,resv,argc,(mxArray**)(argv)); break; - case 1621: flag=_wrap_BerdyHelper_serializeDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 1622: flag=_wrap_BerdyHelper_serializeSensorVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 1623: flag=_wrap_BerdyHelper_serializeDynamicVariablesComputedFromFixedBaseRNEA(resc,resv,argc,(mxArray**)(argv)); break; - case 1624: flag=_wrap_BerdyHelper_extractJointTorquesFromDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 1625: flag=_wrap_BerdyHelper_extractLinkNetExternalWrenchesFromDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; - case 1626: flag=_wrap_BerdyHelper_updateKinematicsFromFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1627: flag=_wrap_BerdyHelper_updateKinematicsFromFixedBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1628: flag=_wrap_BerdyHelper_updateKinematicsFromTraversalFixedBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1629: flag=_wrap_BerdyHelper_setNetExternalWrenchMeasurementFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1630: flag=_wrap_BerdyHelper_getNetExternalWrenchMeasurementFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1631: flag=_wrap_delete_BerdyHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 1632: flag=_wrap_new_BerdySparseMAPSolver(resc,resv,argc,(mxArray**)(argv)); break; - case 1633: flag=_wrap_delete_BerdySparseMAPSolver(resc,resv,argc,(mxArray**)(argv)); break; - case 1634: flag=_wrap_BerdySparseMAPSolver_setDynamicsConstraintsPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1635: flag=_wrap_BerdySparseMAPSolver_setDynamicsRegularizationPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1636: flag=_wrap_BerdySparseMAPSolver_setDynamicsRegularizationPriorExpectedValue(resc,resv,argc,(mxArray**)(argv)); break; - case 1637: flag=_wrap_BerdySparseMAPSolver_setMeasurementsPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1638: flag=_wrap_BerdySparseMAPSolver_dynamicsConstraintsPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 1639: flag=_wrap_BerdySparseMAPSolver_dynamicsRegularizationPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 1640: flag=_wrap_BerdySparseMAPSolver_dynamicsRegularizationPriorExpectedValue(resc,resv,argc,(mxArray**)(argv)); break; - case 1641: flag=_wrap_BerdySparseMAPSolver_measurementsPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; - case 1642: flag=_wrap_BerdySparseMAPSolver_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1643: flag=_wrap_BerdySparseMAPSolver_initialize(resc,resv,argc,(mxArray**)(argv)); break; - case 1644: flag=_wrap_BerdySparseMAPSolver_updateEstimateInformationFixedBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1645: flag=_wrap_BerdySparseMAPSolver_updateEstimateInformationFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1646: flag=_wrap_BerdySparseMAPSolver_doEstimate(resc,resv,argc,(mxArray**)(argv)); break; - case 1647: flag=_wrap_BerdySparseMAPSolver_getLastEstimate(resc,resv,argc,(mxArray**)(argv)); break; - case 1648: flag=_wrap_AttitudeEstimatorState_m_orientation_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1649: flag=_wrap_AttitudeEstimatorState_m_orientation_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1650: flag=_wrap_AttitudeEstimatorState_m_angular_velocity_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1651: flag=_wrap_AttitudeEstimatorState_m_angular_velocity_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1652: flag=_wrap_AttitudeEstimatorState_m_gyroscope_bias_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1653: flag=_wrap_AttitudeEstimatorState_m_gyroscope_bias_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1654: flag=_wrap_new_AttitudeEstimatorState(resc,resv,argc,(mxArray**)(argv)); break; - case 1655: flag=_wrap_delete_AttitudeEstimatorState(resc,resv,argc,(mxArray**)(argv)); break; - case 1656: flag=_wrap_delete_IAttitudeEstimator(resc,resv,argc,(mxArray**)(argv)); break; - case 1657: flag=_wrap_IAttitudeEstimator_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1658: flag=_wrap_IAttitudeEstimator_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; - case 1659: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1660: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 1661: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; - case 1662: flag=_wrap_IAttitudeEstimator_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1663: flag=_wrap_IAttitudeEstimator_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1664: flag=_wrap_IAttitudeEstimator_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; - case 1665: flag=_wrap_IAttitudeEstimator_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1666: flag=_wrap_IAttitudeEstimator_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; - case 1667: flag=_wrap_AttitudeMahonyFilterParameters_time_step_in_seconds_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1668: flag=_wrap_AttitudeMahonyFilterParameters_time_step_in_seconds_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1669: flag=_wrap_AttitudeMahonyFilterParameters_kp_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1670: flag=_wrap_AttitudeMahonyFilterParameters_kp_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1671: flag=_wrap_AttitudeMahonyFilterParameters_ki_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1672: flag=_wrap_AttitudeMahonyFilterParameters_ki_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1673: flag=_wrap_AttitudeMahonyFilterParameters_use_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1674: flag=_wrap_AttitudeMahonyFilterParameters_use_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1675: flag=_wrap_AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1676: flag=_wrap_AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1677: flag=_wrap_new_AttitudeMahonyFilterParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1678: flag=_wrap_delete_AttitudeMahonyFilterParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1679: flag=_wrap_new_AttitudeMahonyFilter(resc,resv,argc,(mxArray**)(argv)); break; - case 1680: flag=_wrap_AttitudeMahonyFilter_useMagnetoMeterMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1681: flag=_wrap_AttitudeMahonyFilter_setConfidenceForMagnetometerMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1682: flag=_wrap_AttitudeMahonyFilter_setGainkp(resc,resv,argc,(mxArray**)(argv)); break; - case 1683: flag=_wrap_AttitudeMahonyFilter_setGainki(resc,resv,argc,(mxArray**)(argv)); break; - case 1684: flag=_wrap_AttitudeMahonyFilter_setTimeStepInSeconds(resc,resv,argc,(mxArray**)(argv)); break; - case 1685: flag=_wrap_AttitudeMahonyFilter_setGravityDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1686: flag=_wrap_AttitudeMahonyFilter_setParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1687: flag=_wrap_AttitudeMahonyFilter_getParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1688: flag=_wrap_AttitudeMahonyFilter_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1689: flag=_wrap_AttitudeMahonyFilter_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; - case 1690: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1691: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 1692: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; - case 1693: flag=_wrap_AttitudeMahonyFilter_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1694: flag=_wrap_AttitudeMahonyFilter_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1695: flag=_wrap_AttitudeMahonyFilter_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; - case 1696: flag=_wrap_AttitudeMahonyFilter_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1697: flag=_wrap_AttitudeMahonyFilter_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; - case 1698: flag=_wrap_delete_AttitudeMahonyFilter(resc,resv,argc,(mxArray**)(argv)); break; - case 1699: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekf_f(resc,resv,argc,(mxArray**)(argv)); break; - case 1700: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekf_h(resc,resv,argc,(mxArray**)(argv)); break; - case 1701: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianF(resc,resv,argc,(mxArray**)(argv)); break; - case 1702: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianH(resc,resv,argc,(mxArray**)(argv)); break; - case 1703: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfPredict(resc,resv,argc,(mxArray**)(argv)); break; - case 1704: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfUpdate(resc,resv,argc,(mxArray**)(argv)); break; - case 1705: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfInit(resc,resv,argc,(mxArray**)(argv)); break; - case 1706: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfReset(resc,resv,argc,(mxArray**)(argv)); break; - case 1707: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1708: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInputVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1709: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInitialState(resc,resv,argc,(mxArray**)(argv)); break; - case 1710: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1711: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetSystemNoiseCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1712: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementNoiseCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1713: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetStateSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1714: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInputSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1715: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetOutputSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1716: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfGetStates(resc,resv,argc,(mxArray**)(argv)); break; - case 1717: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfGetStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1718: flag=_wrap_delete_DiscreteExtendedKalmanFilterHelper(resc,resv,argc,(mxArray**)(argv)); break; - case 1719: flag=_wrap_output_dimensions_with_magnetometer_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1720: flag=_wrap_output_dimensions_without_magnetometer_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1721: flag=_wrap_input_dimensions_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1722: flag=_wrap_AttitudeQuaternionEKFParameters_time_step_in_seconds_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1723: flag=_wrap_AttitudeQuaternionEKFParameters_time_step_in_seconds_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1724: flag=_wrap_AttitudeQuaternionEKFParameters_bias_correlation_time_factor_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1725: flag=_wrap_AttitudeQuaternionEKFParameters_bias_correlation_time_factor_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1726: flag=_wrap_AttitudeQuaternionEKFParameters_accelerometer_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1727: flag=_wrap_AttitudeQuaternionEKFParameters_accelerometer_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1728: flag=_wrap_AttitudeQuaternionEKFParameters_magnetometer_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1729: flag=_wrap_AttitudeQuaternionEKFParameters_magnetometer_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1730: flag=_wrap_AttitudeQuaternionEKFParameters_gyroscope_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1731: flag=_wrap_AttitudeQuaternionEKFParameters_gyroscope_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1732: flag=_wrap_AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1733: flag=_wrap_AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1734: flag=_wrap_AttitudeQuaternionEKFParameters_initial_orientation_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1735: flag=_wrap_AttitudeQuaternionEKFParameters_initial_orientation_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1736: flag=_wrap_AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1737: flag=_wrap_AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1738: flag=_wrap_AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1739: flag=_wrap_AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1740: flag=_wrap_AttitudeQuaternionEKFParameters_use_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1741: flag=_wrap_AttitudeQuaternionEKFParameters_use_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1742: flag=_wrap_new_AttitudeQuaternionEKFParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1743: flag=_wrap_delete_AttitudeQuaternionEKFParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1744: flag=_wrap_new_AttitudeQuaternionEKF(resc,resv,argc,(mxArray**)(argv)); break; - case 1745: flag=_wrap_AttitudeQuaternionEKF_getParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1746: flag=_wrap_AttitudeQuaternionEKF_setParameters(resc,resv,argc,(mxArray**)(argv)); break; - case 1747: flag=_wrap_AttitudeQuaternionEKF_setGravityDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1748: flag=_wrap_AttitudeQuaternionEKF_setTimeStepInSeconds(resc,resv,argc,(mxArray**)(argv)); break; - case 1749: flag=_wrap_AttitudeQuaternionEKF_setBiasCorrelationTimeFactor(resc,resv,argc,(mxArray**)(argv)); break; - case 1750: flag=_wrap_AttitudeQuaternionEKF_useMagnetometerMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1751: flag=_wrap_AttitudeQuaternionEKF_setMeasurementNoiseVariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1752: flag=_wrap_AttitudeQuaternionEKF_setSystemNoiseVariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1753: flag=_wrap_AttitudeQuaternionEKF_setInitialStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; - case 1754: flag=_wrap_AttitudeQuaternionEKF_initializeFilter(resc,resv,argc,(mxArray**)(argv)); break; - case 1755: flag=_wrap_AttitudeQuaternionEKF_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; - case 1756: flag=_wrap_AttitudeQuaternionEKF_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; - case 1757: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1758: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; - case 1759: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; - case 1760: flag=_wrap_AttitudeQuaternionEKF_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1761: flag=_wrap_AttitudeQuaternionEKF_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1762: flag=_wrap_AttitudeQuaternionEKF_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; - case 1763: flag=_wrap_AttitudeQuaternionEKF_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; - case 1764: flag=_wrap_AttitudeQuaternionEKF_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; - case 1765: flag=_wrap_delete_AttitudeQuaternionEKF(resc,resv,argc,(mxArray**)(argv)); break; - case 1766: flag=_wrap_estimateInertialParametersFromLinkBoundingBoxesAndTotalMass(resc,resv,argc,(mxArray**)(argv)); break; - case 1767: flag=_wrap_computeBoundingBoxFromShape(resc,resv,argc,(mxArray**)(argv)); break; - case 1768: flag=_wrap_computeBoxVertices(resc,resv,argc,(mxArray**)(argv)); break; - case 1769: flag=_wrap_new_KinDynComputations(resc,resv,argc,(mxArray**)(argv)); break; - case 1770: flag=_wrap_delete_KinDynComputations(resc,resv,argc,(mxArray**)(argv)); break; - case 1771: flag=_wrap_KinDynComputations_loadRobotModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1772: flag=_wrap_KinDynComputations_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 1773: flag=_wrap_KinDynComputations_setFrameVelocityRepresentation(resc,resv,argc,(mxArray**)(argv)); break; - case 1774: flag=_wrap_KinDynComputations_getFrameVelocityRepresentation(resc,resv,argc,(mxArray**)(argv)); break; - case 1775: flag=_wrap_KinDynComputations_getNrOfDegreesOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; - case 1776: flag=_wrap_KinDynComputations_getDescriptionOfDegreeOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; - case 1777: flag=_wrap_KinDynComputations_getDescriptionOfDegreesOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; - case 1778: flag=_wrap_KinDynComputations_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; - case 1779: flag=_wrap_KinDynComputations_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; - case 1780: flag=_wrap_KinDynComputations_getFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1781: flag=_wrap_KinDynComputations_setFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; - case 1782: flag=_wrap_KinDynComputations_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1783: flag=_wrap_KinDynComputations_getRobotModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1784: flag=_wrap_KinDynComputations_getRelativeJacobianSparsityPattern(resc,resv,argc,(mxArray**)(argv)); break; - case 1785: flag=_wrap_KinDynComputations_getFrameFreeFloatingJacobianSparsityPattern(resc,resv,argc,(mxArray**)(argv)); break; - case 1786: flag=_wrap_KinDynComputations_setJointPos(resc,resv,argc,(mxArray**)(argv)); break; - case 1787: flag=_wrap_KinDynComputations_setRobotState(resc,resv,argc,(mxArray**)(argv)); break; - case 1788: flag=_wrap_KinDynComputations_getRobotState(resc,resv,argc,(mxArray**)(argv)); break; - case 1789: flag=_wrap_KinDynComputations_getWorldBaseTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1790: flag=_wrap_KinDynComputations_getBaseTwist(resc,resv,argc,(mxArray**)(argv)); break; - case 1791: flag=_wrap_KinDynComputations_getJointPos(resc,resv,argc,(mxArray**)(argv)); break; - case 1792: flag=_wrap_KinDynComputations_getJointVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1793: flag=_wrap_KinDynComputations_getModelVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1794: flag=_wrap_KinDynComputations_getFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1795: flag=_wrap_KinDynComputations_getFrameName(resc,resv,argc,(mxArray**)(argv)); break; - case 1796: flag=_wrap_KinDynComputations_getWorldTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1797: flag=_wrap_KinDynComputations_getWorldTransformsAsHomogeneous(resc,resv,argc,(mxArray**)(argv)); break; - case 1798: flag=_wrap_KinDynComputations_getRelativeTransformExplicit(resc,resv,argc,(mxArray**)(argv)); break; - case 1799: flag=_wrap_KinDynComputations_getRelativeTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1800: flag=_wrap_KinDynComputations_getFrameVel(resc,resv,argc,(mxArray**)(argv)); break; - case 1801: flag=_wrap_KinDynComputations_getFrameAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1802: flag=_wrap_KinDynComputations_getFrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1803: flag=_wrap_KinDynComputations_getRelativeJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1804: flag=_wrap_KinDynComputations_getRelativeJacobianExplicit(resc,resv,argc,(mxArray**)(argv)); break; - case 1805: flag=_wrap_KinDynComputations_getFrameBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1806: flag=_wrap_KinDynComputations_getCenterOfMassPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1807: flag=_wrap_KinDynComputations_getCenterOfMassVelocity(resc,resv,argc,(mxArray**)(argv)); break; - case 1808: flag=_wrap_KinDynComputations_getCenterOfMassJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1809: flag=_wrap_KinDynComputations_getCenterOfMassBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; - case 1810: flag=_wrap_KinDynComputations_getAverageVelocity(resc,resv,argc,(mxArray**)(argv)); break; - case 1811: flag=_wrap_KinDynComputations_getAverageVelocityJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1812: flag=_wrap_KinDynComputations_getCentroidalAverageVelocity(resc,resv,argc,(mxArray**)(argv)); break; - case 1813: flag=_wrap_KinDynComputations_getCentroidalAverageVelocityJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1814: flag=_wrap_KinDynComputations_getLinearAngularMomentum(resc,resv,argc,(mxArray**)(argv)); break; - case 1815: flag=_wrap_KinDynComputations_getLinearAngularMomentumJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1816: flag=_wrap_KinDynComputations_getCentroidalTotalMomentum(resc,resv,argc,(mxArray**)(argv)); break; - case 1817: flag=_wrap_KinDynComputations_getCentroidalTotalMomentumJacobian(resc,resv,argc,(mxArray**)(argv)); break; - case 1818: flag=_wrap_KinDynComputations_getFreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; - case 1819: flag=_wrap_KinDynComputations_inverseDynamics(resc,resv,argc,(mxArray**)(argv)); break; - case 1820: flag=_wrap_KinDynComputations_inverseDynamicsWithInternalJointForceTorques(resc,resv,argc,(mxArray**)(argv)); break; - case 1821: flag=_wrap_KinDynComputations_generalizedBiasForces(resc,resv,argc,(mxArray**)(argv)); break; - case 1822: flag=_wrap_KinDynComputations_generalizedGravityForces(resc,resv,argc,(mxArray**)(argv)); break; - case 1823: flag=_wrap_KinDynComputations_generalizedExternalForces(resc,resv,argc,(mxArray**)(argv)); break; - case 1824: flag=_wrap_KinDynComputations_inverseDynamicsInertialParametersRegressor(resc,resv,argc,(mxArray**)(argv)); break; - case 1825: flag=_wrap_Matrix4x4Vector_pop(resc,resv,argc,(mxArray**)(argv)); break; - case 1826: flag=_wrap_Matrix4x4Vector_brace(resc,resv,argc,(mxArray**)(argv)); break; - case 1827: flag=_wrap_Matrix4x4Vector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; - case 1828: flag=_wrap_Matrix4x4Vector_append(resc,resv,argc,(mxArray**)(argv)); break; - case 1829: flag=_wrap_Matrix4x4Vector_empty(resc,resv,argc,(mxArray**)(argv)); break; - case 1830: flag=_wrap_Matrix4x4Vector_size(resc,resv,argc,(mxArray**)(argv)); break; - case 1831: flag=_wrap_Matrix4x4Vector_swap(resc,resv,argc,(mxArray**)(argv)); break; - case 1832: flag=_wrap_Matrix4x4Vector_begin(resc,resv,argc,(mxArray**)(argv)); break; - case 1833: flag=_wrap_Matrix4x4Vector_end(resc,resv,argc,(mxArray**)(argv)); break; - case 1834: flag=_wrap_Matrix4x4Vector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; - case 1835: flag=_wrap_Matrix4x4Vector_rend(resc,resv,argc,(mxArray**)(argv)); break; - case 1836: flag=_wrap_Matrix4x4Vector_clear(resc,resv,argc,(mxArray**)(argv)); break; - case 1837: flag=_wrap_Matrix4x4Vector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; - case 1838: flag=_wrap_Matrix4x4Vector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1839: flag=_wrap_Matrix4x4Vector_erase(resc,resv,argc,(mxArray**)(argv)); break; - case 1840: flag=_wrap_new_Matrix4x4Vector(resc,resv,argc,(mxArray**)(argv)); break; - case 1841: flag=_wrap_Matrix4x4Vector_push_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1842: flag=_wrap_Matrix4x4Vector_front(resc,resv,argc,(mxArray**)(argv)); break; - case 1843: flag=_wrap_Matrix4x4Vector_back(resc,resv,argc,(mxArray**)(argv)); break; - case 1844: flag=_wrap_Matrix4x4Vector_assign(resc,resv,argc,(mxArray**)(argv)); break; - case 1845: flag=_wrap_Matrix4x4Vector_resize(resc,resv,argc,(mxArray**)(argv)); break; - case 1846: flag=_wrap_Matrix4x4Vector_insert(resc,resv,argc,(mxArray**)(argv)); break; - case 1847: flag=_wrap_Matrix4x4Vector_reserve(resc,resv,argc,(mxArray**)(argv)); break; - case 1848: flag=_wrap_Matrix4x4Vector_capacity(resc,resv,argc,(mxArray**)(argv)); break; - case 1849: flag=_wrap_Matrix4x4Vector_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; - case 1850: flag=_wrap_delete_Matrix4x4Vector(resc,resv,argc,(mxArray**)(argv)); break; - case 1851: flag=_wrap_ICameraAnimator_enableMouseControl(resc,resv,argc,(mxArray**)(argv)); break; - case 1852: flag=_wrap_ICameraAnimator_getMoveSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1853: flag=_wrap_ICameraAnimator_setMoveSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1854: flag=_wrap_ICameraAnimator_getRotateSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1855: flag=_wrap_ICameraAnimator_setRotateSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1856: flag=_wrap_ICameraAnimator_getZoomSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1857: flag=_wrap_ICameraAnimator_setZoomSpeed(resc,resv,argc,(mxArray**)(argv)); break; - case 1858: flag=_wrap_delete_ICameraAnimator(resc,resv,argc,(mxArray**)(argv)); break; - case 1859: flag=_wrap_delete_ICamera(resc,resv,argc,(mxArray**)(argv)); break; - case 1860: flag=_wrap_ICamera_setPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1861: flag=_wrap_ICamera_setTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 1862: flag=_wrap_ICamera_getPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1863: flag=_wrap_ICamera_getTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 1864: flag=_wrap_ICamera_setUpVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1865: flag=_wrap_ICamera_animator(resc,resv,argc,(mxArray**)(argv)); break; - case 1866: flag=_wrap_ColorViz_r_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1867: flag=_wrap_ColorViz_r_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1868: flag=_wrap_ColorViz_g_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1869: flag=_wrap_ColorViz_g_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1870: flag=_wrap_ColorViz_b_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1871: flag=_wrap_ColorViz_b_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1872: flag=_wrap_ColorViz_a_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1873: flag=_wrap_ColorViz_a_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1874: flag=_wrap_new_ColorViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1875: flag=_wrap_delete_ColorViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1876: flag=_wrap_PixelViz_width_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1877: flag=_wrap_PixelViz_width_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1878: flag=_wrap_PixelViz_height_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1879: flag=_wrap_PixelViz_height_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1880: flag=_wrap_new_PixelViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1881: flag=_wrap_delete_PixelViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1882: flag=_wrap_delete_ILight(resc,resv,argc,(mxArray**)(argv)); break; - case 1883: flag=_wrap_ILight_getName(resc,resv,argc,(mxArray**)(argv)); break; - case 1884: flag=_wrap_ILight_setType(resc,resv,argc,(mxArray**)(argv)); break; - case 1885: flag=_wrap_ILight_getType(resc,resv,argc,(mxArray**)(argv)); break; - case 1886: flag=_wrap_ILight_setPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1887: flag=_wrap_ILight_getPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1888: flag=_wrap_ILight_setDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1889: flag=_wrap_ILight_getDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1890: flag=_wrap_ILight_setAmbientColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1891: flag=_wrap_ILight_getAmbientColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1892: flag=_wrap_ILight_setSpecularColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1893: flag=_wrap_ILight_getSpecularColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1894: flag=_wrap_ILight_setDiffuseColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1895: flag=_wrap_ILight_getDiffuseColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1896: flag=_wrap_delete_IEnvironment(resc,resv,argc,(mxArray**)(argv)); break; - case 1897: flag=_wrap_IEnvironment_getElements(resc,resv,argc,(mxArray**)(argv)); break; - case 1898: flag=_wrap_IEnvironment_setElementVisibility(resc,resv,argc,(mxArray**)(argv)); break; - case 1899: flag=_wrap_IEnvironment_setBackgroundColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1900: flag=_wrap_IEnvironment_setFloorGridColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1901: flag=_wrap_IEnvironment_setAmbientLight(resc,resv,argc,(mxArray**)(argv)); break; - case 1902: flag=_wrap_IEnvironment_getLights(resc,resv,argc,(mxArray**)(argv)); break; - case 1903: flag=_wrap_IEnvironment_addLight(resc,resv,argc,(mxArray**)(argv)); break; - case 1904: flag=_wrap_IEnvironment_lightViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1905: flag=_wrap_IEnvironment_removeLight(resc,resv,argc,(mxArray**)(argv)); break; - case 1906: flag=_wrap_delete_IJetsVisualization(resc,resv,argc,(mxArray**)(argv)); break; - case 1907: flag=_wrap_IJetsVisualization_setJetsFrames(resc,resv,argc,(mxArray**)(argv)); break; - case 1908: flag=_wrap_IJetsVisualization_getNrOfJets(resc,resv,argc,(mxArray**)(argv)); break; - case 1909: flag=_wrap_IJetsVisualization_getJetDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1910: flag=_wrap_IJetsVisualization_setJetDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 1911: flag=_wrap_IJetsVisualization_setJetColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1912: flag=_wrap_IJetsVisualization_setJetsDimensions(resc,resv,argc,(mxArray**)(argv)); break; - case 1913: flag=_wrap_IJetsVisualization_setJetsIntensity(resc,resv,argc,(mxArray**)(argv)); break; - case 1914: flag=_wrap_delete_ILabel(resc,resv,argc,(mxArray**)(argv)); break; - case 1915: flag=_wrap_ILabel_setText(resc,resv,argc,(mxArray**)(argv)); break; - case 1916: flag=_wrap_ILabel_getText(resc,resv,argc,(mxArray**)(argv)); break; - case 1917: flag=_wrap_ILabel_setSize(resc,resv,argc,(mxArray**)(argv)); break; - case 1918: flag=_wrap_ILabel_width(resc,resv,argc,(mxArray**)(argv)); break; - case 1919: flag=_wrap_ILabel_height(resc,resv,argc,(mxArray**)(argv)); break; - case 1920: flag=_wrap_ILabel_setPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1921: flag=_wrap_ILabel_getPosition(resc,resv,argc,(mxArray**)(argv)); break; - case 1922: flag=_wrap_ILabel_setColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1923: flag=_wrap_ILabel_setVisible(resc,resv,argc,(mxArray**)(argv)); break; - case 1924: flag=_wrap_delete_IVectorsVisualization(resc,resv,argc,(mxArray**)(argv)); break; - case 1925: flag=_wrap_IVectorsVisualization_addVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1926: flag=_wrap_IVectorsVisualization_getNrOfVectors(resc,resv,argc,(mxArray**)(argv)); break; - case 1927: flag=_wrap_IVectorsVisualization_getVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1928: flag=_wrap_IVectorsVisualization_updateVector(resc,resv,argc,(mxArray**)(argv)); break; - case 1929: flag=_wrap_IVectorsVisualization_setVectorColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1930: flag=_wrap_IVectorsVisualization_setVectorsDefaultColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1931: flag=_wrap_IVectorsVisualization_setVectorsColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1932: flag=_wrap_IVectorsVisualization_setVectorsAspect(resc,resv,argc,(mxArray**)(argv)); break; - case 1933: flag=_wrap_IVectorsVisualization_setVisible(resc,resv,argc,(mxArray**)(argv)); break; - case 1934: flag=_wrap_IVectorsVisualization_getVectorLabel(resc,resv,argc,(mxArray**)(argv)); break; - case 1935: flag=_wrap_delete_IFrameVisualization(resc,resv,argc,(mxArray**)(argv)); break; - case 1936: flag=_wrap_IFrameVisualization_addFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1937: flag=_wrap_IFrameVisualization_setVisible(resc,resv,argc,(mxArray**)(argv)); break; - case 1938: flag=_wrap_IFrameVisualization_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; - case 1939: flag=_wrap_IFrameVisualization_getFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1940: flag=_wrap_IFrameVisualization_updateFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 1941: flag=_wrap_IFrameVisualization_getFrameLabel(resc,resv,argc,(mxArray**)(argv)); break; - case 1942: flag=_wrap_delete_IModelVisualization(resc,resv,argc,(mxArray**)(argv)); break; - case 1943: flag=_wrap_IModelVisualization_setPositions(resc,resv,argc,(mxArray**)(argv)); break; - case 1944: flag=_wrap_IModelVisualization_setLinkPositions(resc,resv,argc,(mxArray**)(argv)); break; - case 1945: flag=_wrap_IModelVisualization_model(resc,resv,argc,(mxArray**)(argv)); break; - case 1946: flag=_wrap_IModelVisualization_getInstanceName(resc,resv,argc,(mxArray**)(argv)); break; - case 1947: flag=_wrap_IModelVisualization_setModelVisibility(resc,resv,argc,(mxArray**)(argv)); break; - case 1948: flag=_wrap_IModelVisualization_setModelColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1949: flag=_wrap_IModelVisualization_resetModelColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1950: flag=_wrap_IModelVisualization_setLinkColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1951: flag=_wrap_IModelVisualization_resetLinkColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1952: flag=_wrap_IModelVisualization_getLinkNames(resc,resv,argc,(mxArray**)(argv)); break; - case 1953: flag=_wrap_IModelVisualization_setLinkVisibility(resc,resv,argc,(mxArray**)(argv)); break; - case 1954: flag=_wrap_IModelVisualization_getFeatures(resc,resv,argc,(mxArray**)(argv)); break; - case 1955: flag=_wrap_IModelVisualization_setFeatureVisibility(resc,resv,argc,(mxArray**)(argv)); break; - case 1956: flag=_wrap_IModelVisualization_jets(resc,resv,argc,(mxArray**)(argv)); break; - case 1957: flag=_wrap_IModelVisualization_getWorldLinkTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1958: flag=_wrap_IModelVisualization_getWorldFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 1959: flag=_wrap_IModelVisualization_label(resc,resv,argc,(mxArray**)(argv)); break; - case 1960: flag=_wrap_delete_ITexture(resc,resv,argc,(mxArray**)(argv)); break; - case 1961: flag=_wrap_ITexture_environment(resc,resv,argc,(mxArray**)(argv)); break; - case 1962: flag=_wrap_ITexture_getPixelColor(resc,resv,argc,(mxArray**)(argv)); break; - case 1963: flag=_wrap_ITexture_getPixels(resc,resv,argc,(mxArray**)(argv)); break; - case 1964: flag=_wrap_ITexture_drawToFile(resc,resv,argc,(mxArray**)(argv)); break; - case 1965: flag=_wrap_ITexture_enableDraw(resc,resv,argc,(mxArray**)(argv)); break; - case 1966: flag=_wrap_ITexture_width(resc,resv,argc,(mxArray**)(argv)); break; - case 1967: flag=_wrap_ITexture_height(resc,resv,argc,(mxArray**)(argv)); break; - case 1968: flag=_wrap_ITexture_setSubDrawArea(resc,resv,argc,(mxArray**)(argv)); break; - case 1969: flag=_wrap_VisualizerOptions_verbose_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1970: flag=_wrap_VisualizerOptions_verbose_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1971: flag=_wrap_VisualizerOptions_winWidth_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1972: flag=_wrap_VisualizerOptions_winWidth_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1973: flag=_wrap_VisualizerOptions_winHeight_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1974: flag=_wrap_VisualizerOptions_winHeight_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1975: flag=_wrap_VisualizerOptions_rootFrameArrowsDimension_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1976: flag=_wrap_VisualizerOptions_rootFrameArrowsDimension_set(resc,resv,argc,(mxArray**)(argv)); break; - case 1977: flag=_wrap_new_VisualizerOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1978: flag=_wrap_delete_VisualizerOptions(resc,resv,argc,(mxArray**)(argv)); break; - case 1979: flag=_wrap_delete_ITexturesHandler(resc,resv,argc,(mxArray**)(argv)); break; - case 1980: flag=_wrap_ITexturesHandler_add(resc,resv,argc,(mxArray**)(argv)); break; - case 1981: flag=_wrap_ITexturesHandler_get(resc,resv,argc,(mxArray**)(argv)); break; - case 1982: flag=_wrap_new_Visualizer(resc,resv,argc,(mxArray**)(argv)); break; - case 1983: flag=_wrap_delete_Visualizer(resc,resv,argc,(mxArray**)(argv)); break; - case 1984: flag=_wrap_Visualizer_init(resc,resv,argc,(mxArray**)(argv)); break; - case 1985: flag=_wrap_Visualizer_getNrOfVisualizedModels(resc,resv,argc,(mxArray**)(argv)); break; - case 1986: flag=_wrap_Visualizer_getModelInstanceName(resc,resv,argc,(mxArray**)(argv)); break; - case 1987: flag=_wrap_Visualizer_getModelInstanceIndex(resc,resv,argc,(mxArray**)(argv)); break; - case 1988: flag=_wrap_Visualizer_addModel(resc,resv,argc,(mxArray**)(argv)); break; - case 1989: flag=_wrap_Visualizer_modelViz(resc,resv,argc,(mxArray**)(argv)); break; - case 1990: flag=_wrap_Visualizer_camera(resc,resv,argc,(mxArray**)(argv)); break; - case 1991: flag=_wrap_Visualizer_enviroment(resc,resv,argc,(mxArray**)(argv)); break; - case 1992: flag=_wrap_Visualizer_environment(resc,resv,argc,(mxArray**)(argv)); break; - case 1993: flag=_wrap_Visualizer_vectors(resc,resv,argc,(mxArray**)(argv)); break; - case 1994: flag=_wrap_Visualizer_frames(resc,resv,argc,(mxArray**)(argv)); break; - case 1995: flag=_wrap_Visualizer_textures(resc,resv,argc,(mxArray**)(argv)); break; - case 1996: flag=_wrap_Visualizer_getLabel(resc,resv,argc,(mxArray**)(argv)); break; - case 1997: flag=_wrap_Visualizer_width(resc,resv,argc,(mxArray**)(argv)); break; - case 1998: flag=_wrap_Visualizer_height(resc,resv,argc,(mxArray**)(argv)); break; - case 1999: flag=_wrap_Visualizer_run(resc,resv,argc,(mxArray**)(argv)); break; - case 2000: flag=_wrap_Visualizer_draw(resc,resv,argc,(mxArray**)(argv)); break; - case 2001: flag=_wrap_Visualizer_subDraw(resc,resv,argc,(mxArray**)(argv)); break; - case 2002: flag=_wrap_Visualizer_drawToFile(resc,resv,argc,(mxArray**)(argv)); break; - case 2003: flag=_wrap_Visualizer_close(resc,resv,argc,(mxArray**)(argv)); break; - case 2004: flag=_wrap_Visualizer_isWindowActive(resc,resv,argc,(mxArray**)(argv)); break; - case 2005: flag=_wrap_Visualizer_setColorPalette(resc,resv,argc,(mxArray**)(argv)); break; - case 2006: flag=_wrap_Polygon_m_vertices_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2007: flag=_wrap_Polygon_m_vertices_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2008: flag=_wrap_new_Polygon(resc,resv,argc,(mxArray**)(argv)); break; - case 2009: flag=_wrap_Polygon_setNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; - case 2010: flag=_wrap_Polygon_getNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; - case 2011: flag=_wrap_Polygon_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 2012: flag=_wrap_Polygon_applyTransform(resc,resv,argc,(mxArray**)(argv)); break; - case 2013: flag=_wrap_Polygon_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 2014: flag=_wrap_Polygon_XYRectangleFromOffsets(resc,resv,argc,(mxArray**)(argv)); break; - case 2015: flag=_wrap_delete_Polygon(resc,resv,argc,(mxArray**)(argv)); break; - case 2016: flag=_wrap_Polygon2D_m_vertices_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2017: flag=_wrap_Polygon2D_m_vertices_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2018: flag=_wrap_new_Polygon2D(resc,resv,argc,(mxArray**)(argv)); break; - case 2019: flag=_wrap_Polygon2D_setNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; - case 2020: flag=_wrap_Polygon2D_getNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; - case 2021: flag=_wrap_Polygon2D_isValid(resc,resv,argc,(mxArray**)(argv)); break; - case 2022: flag=_wrap_Polygon2D_paren(resc,resv,argc,(mxArray**)(argv)); break; - case 2023: flag=_wrap_delete_Polygon2D(resc,resv,argc,(mxArray**)(argv)); break; - case 2024: flag=_wrap_ConvexHullProjectionConstraint_setActive(resc,resv,argc,(mxArray**)(argv)); break; - case 2025: flag=_wrap_ConvexHullProjectionConstraint_isActive(resc,resv,argc,(mxArray**)(argv)); break; - case 2026: flag=_wrap_ConvexHullProjectionConstraint_getNrOfConstraints(resc,resv,argc,(mxArray**)(argv)); break; - case 2027: flag=_wrap_ConvexHullProjectionConstraint_projectedConvexHull_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2028: flag=_wrap_ConvexHullProjectionConstraint_projectedConvexHull_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2029: flag=_wrap_ConvexHullProjectionConstraint_A_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2030: flag=_wrap_ConvexHullProjectionConstraint_A_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2031: flag=_wrap_ConvexHullProjectionConstraint_b_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2032: flag=_wrap_ConvexHullProjectionConstraint_b_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2033: flag=_wrap_ConvexHullProjectionConstraint_P_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2034: flag=_wrap_ConvexHullProjectionConstraint_P_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2035: flag=_wrap_ConvexHullProjectionConstraint_Pdirection_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2036: flag=_wrap_ConvexHullProjectionConstraint_Pdirection_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2037: flag=_wrap_ConvexHullProjectionConstraint_AtimesP_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2038: flag=_wrap_ConvexHullProjectionConstraint_AtimesP_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2039: flag=_wrap_ConvexHullProjectionConstraint_o_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2040: flag=_wrap_ConvexHullProjectionConstraint_o_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2041: flag=_wrap_ConvexHullProjectionConstraint_buildConvexHull(resc,resv,argc,(mxArray**)(argv)); break; - case 2042: flag=_wrap_ConvexHullProjectionConstraint_supportFrameIndices_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2043: flag=_wrap_ConvexHullProjectionConstraint_supportFrameIndices_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2044: flag=_wrap_ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_get(resc,resv,argc,(mxArray**)(argv)); break; - case 2045: flag=_wrap_ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_set(resc,resv,argc,(mxArray**)(argv)); break; - case 2046: flag=_wrap_ConvexHullProjectionConstraint_project(resc,resv,argc,(mxArray**)(argv)); break; - case 2047: flag=_wrap_ConvexHullProjectionConstraint_computeMargin(resc,resv,argc,(mxArray**)(argv)); break; - case 2048: flag=_wrap_ConvexHullProjectionConstraint_setProjectionAlongDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 2049: flag=_wrap_ConvexHullProjectionConstraint_projectAlongDirection(resc,resv,argc,(mxArray**)(argv)); break; - case 2050: flag=_wrap_new_ConvexHullProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2051: flag=_wrap_delete_ConvexHullProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2052: flag=_wrap_sizeOfRotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; - case 2053: flag=_wrap_new_InverseKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 2054: flag=_wrap_delete_InverseKinematics(resc,resv,argc,(mxArray**)(argv)); break; - case 2055: flag=_wrap_InverseKinematics_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; - case 2056: flag=_wrap_InverseKinematics_setModel(resc,resv,argc,(mxArray**)(argv)); break; - case 2057: flag=_wrap_InverseKinematics_setJointLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 2058: flag=_wrap_InverseKinematics_getJointLimits(resc,resv,argc,(mxArray**)(argv)); break; - case 2059: flag=_wrap_InverseKinematics_clearProblem(resc,resv,argc,(mxArray**)(argv)); break; - case 2060: flag=_wrap_InverseKinematics_setFloatingBaseOnFrameNamed(resc,resv,argc,(mxArray**)(argv)); break; - case 2061: flag=_wrap_InverseKinematics_setCurrentRobotConfiguration(resc,resv,argc,(mxArray**)(argv)); break; - case 2062: flag=_wrap_InverseKinematics_setJointConfiguration(resc,resv,argc,(mxArray**)(argv)); break; - case 2063: flag=_wrap_InverseKinematics_setRotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; - case 2064: flag=_wrap_InverseKinematics_rotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; - case 2065: flag=_wrap_InverseKinematics_setMaxIterations(resc,resv,argc,(mxArray**)(argv)); break; - case 2066: flag=_wrap_InverseKinematics_maxIterations(resc,resv,argc,(mxArray**)(argv)); break; - case 2067: flag=_wrap_InverseKinematics_setMaxCPUTime(resc,resv,argc,(mxArray**)(argv)); break; - case 2068: flag=_wrap_InverseKinematics_maxCPUTime(resc,resv,argc,(mxArray**)(argv)); break; - case 2069: flag=_wrap_InverseKinematics_setCostTolerance(resc,resv,argc,(mxArray**)(argv)); break; - case 2070: flag=_wrap_InverseKinematics_costTolerance(resc,resv,argc,(mxArray**)(argv)); break; - case 2071: flag=_wrap_InverseKinematics_setConstraintsTolerance(resc,resv,argc,(mxArray**)(argv)); break; - case 2072: flag=_wrap_InverseKinematics_constraintsTolerance(resc,resv,argc,(mxArray**)(argv)); break; - case 2073: flag=_wrap_InverseKinematics_setVerbosity(resc,resv,argc,(mxArray**)(argv)); break; - case 2074: flag=_wrap_InverseKinematics_linearSolverName(resc,resv,argc,(mxArray**)(argv)); break; - case 2075: flag=_wrap_InverseKinematics_setLinearSolverName(resc,resv,argc,(mxArray**)(argv)); break; - case 2076: flag=_wrap_InverseKinematics_addFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2077: flag=_wrap_InverseKinematics_addFramePositionConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2078: flag=_wrap_InverseKinematics_addFrameRotationConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2079: flag=_wrap_InverseKinematics_activateFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2080: flag=_wrap_InverseKinematics_deactivateFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2081: flag=_wrap_InverseKinematics_isFrameConstraintActive(resc,resv,argc,(mxArray**)(argv)); break; - case 2082: flag=_wrap_InverseKinematics_addCenterOfMassProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2083: flag=_wrap_InverseKinematics_getCenterOfMassProjectionMargin(resc,resv,argc,(mxArray**)(argv)); break; - case 2084: flag=_wrap_InverseKinematics_getCenterOfMassProjectConstraintConvexHull(resc,resv,argc,(mxArray**)(argv)); break; - case 2085: flag=_wrap_InverseKinematics_addTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2086: flag=_wrap_InverseKinematics_addPositionTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2087: flag=_wrap_InverseKinematics_addRotationTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2088: flag=_wrap_InverseKinematics_updateTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2089: flag=_wrap_InverseKinematics_updatePositionTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2090: flag=_wrap_InverseKinematics_updateRotationTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2091: flag=_wrap_InverseKinematics_setDefaultTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; - case 2092: flag=_wrap_InverseKinematics_defaultTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; - case 2093: flag=_wrap_InverseKinematics_setTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; - case 2094: flag=_wrap_InverseKinematics_targetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; - case 2095: flag=_wrap_InverseKinematics_setDesiredFullJointsConfiguration(resc,resv,argc,(mxArray**)(argv)); break; - case 2096: flag=_wrap_InverseKinematics_setDesiredReducedJointConfiguration(resc,resv,argc,(mxArray**)(argv)); break; - case 2097: flag=_wrap_InverseKinematics_setFullJointsInitialCondition(resc,resv,argc,(mxArray**)(argv)); break; - case 2098: flag=_wrap_InverseKinematics_setReducedInitialCondition(resc,resv,argc,(mxArray**)(argv)); break; - case 2099: flag=_wrap_InverseKinematics_solve(resc,resv,argc,(mxArray**)(argv)); break; - case 2100: flag=_wrap_InverseKinematics_getFullJointsSolution(resc,resv,argc,(mxArray**)(argv)); break; - case 2101: flag=_wrap_InverseKinematics_getReducedSolution(resc,resv,argc,(mxArray**)(argv)); break; - case 2102: flag=_wrap_InverseKinematics_getPoseForFrame(resc,resv,argc,(mxArray**)(argv)); break; - case 2103: flag=_wrap_InverseKinematics_fullModel(resc,resv,argc,(mxArray**)(argv)); break; - case 2104: flag=_wrap_InverseKinematics_reducedModel(resc,resv,argc,(mxArray**)(argv)); break; - case 2105: flag=_wrap_InverseKinematics_setCOMTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2106: flag=_wrap_InverseKinematics_setCOMAsConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2107: flag=_wrap_InverseKinematics_setCOMAsConstraintTolerance(resc,resv,argc,(mxArray**)(argv)); break; - case 2108: flag=_wrap_InverseKinematics_isCOMAConstraint(resc,resv,argc,(mxArray**)(argv)); break; - case 2109: flag=_wrap_InverseKinematics_isCOMTargetActive(resc,resv,argc,(mxArray**)(argv)); break; - case 2110: flag=_wrap_InverseKinematics_deactivateCOMTarget(resc,resv,argc,(mxArray**)(argv)); break; - case 2111: flag=_wrap_InverseKinematics_setCOMConstraintProjectionDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 71: flag=_wrap_MatrixDynSizeVector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 72: flag=_wrap_MatrixDynSizeVector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 73: flag=_wrap_MatrixDynSizeVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 74: flag=_wrap_MatrixDynSizeVector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 75: flag=_wrap_MatrixDynSizeVector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 76: flag=_wrap_MatrixDynSizeVector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 77: flag=_wrap_MatrixDynSizeVector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 78: flag=_wrap_MatrixDynSizeVector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 79: flag=_wrap_MatrixDynSizeVector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 80: flag=_wrap_MatrixDynSizeVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 81: flag=_wrap_MatrixDynSizeVector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 82: flag=_wrap_MatrixDynSizeVector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 83: flag=_wrap_MatrixDynSizeVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 84: flag=_wrap_MatrixDynSizeVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 85: flag=_wrap_MatrixDynSizeVector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 86: flag=_wrap_new_MatrixDynSizeVector(resc,resv,argc,(mxArray**)(argv)); break; + case 87: flag=_wrap_MatrixDynSizeVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 88: flag=_wrap_MatrixDynSizeVector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 89: flag=_wrap_MatrixDynSizeVector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 90: flag=_wrap_MatrixDynSizeVector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 91: flag=_wrap_MatrixDynSizeVector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 92: flag=_wrap_MatrixDynSizeVector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 93: flag=_wrap_MatrixDynSizeVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 94: flag=_wrap_MatrixDynSizeVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 95: flag=_wrap_delete_MatrixDynSizeVector(resc,resv,argc,(mxArray**)(argv)); break; + case 96: flag=_wrap_VectorDynSizeVector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 97: flag=_wrap_VectorDynSizeVector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 98: flag=_wrap_VectorDynSizeVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 99: flag=_wrap_VectorDynSizeVector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 100: flag=_wrap_VectorDynSizeVector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 101: flag=_wrap_VectorDynSizeVector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 102: flag=_wrap_VectorDynSizeVector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 103: flag=_wrap_VectorDynSizeVector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 104: flag=_wrap_VectorDynSizeVector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 105: flag=_wrap_VectorDynSizeVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 106: flag=_wrap_VectorDynSizeVector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 107: flag=_wrap_VectorDynSizeVector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 108: flag=_wrap_VectorDynSizeVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 109: flag=_wrap_VectorDynSizeVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 110: flag=_wrap_VectorDynSizeVector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 111: flag=_wrap_new_VectorDynSizeVector(resc,resv,argc,(mxArray**)(argv)); break; + case 112: flag=_wrap_VectorDynSizeVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 113: flag=_wrap_VectorDynSizeVector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 114: flag=_wrap_VectorDynSizeVector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 115: flag=_wrap_VectorDynSizeVector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 116: flag=_wrap_VectorDynSizeVector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 117: flag=_wrap_VectorDynSizeVector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 118: flag=_wrap_VectorDynSizeVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 119: flag=_wrap_VectorDynSizeVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 120: flag=_wrap_delete_VectorDynSizeVector(resc,resv,argc,(mxArray**)(argv)); break; + case 121: flag=_wrap_IndexVector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 122: flag=_wrap_IndexVector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 123: flag=_wrap_IndexVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 124: flag=_wrap_IndexVector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 125: flag=_wrap_IndexVector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 126: flag=_wrap_IndexVector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 127: flag=_wrap_IndexVector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 128: flag=_wrap_IndexVector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 129: flag=_wrap_IndexVector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 130: flag=_wrap_IndexVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 131: flag=_wrap_IndexVector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 132: flag=_wrap_IndexVector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 133: flag=_wrap_IndexVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 134: flag=_wrap_IndexVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 135: flag=_wrap_IndexVector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 136: flag=_wrap_new_IndexVector(resc,resv,argc,(mxArray**)(argv)); break; + case 137: flag=_wrap_IndexVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 138: flag=_wrap_IndexVector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 139: flag=_wrap_IndexVector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 140: flag=_wrap_IndexVector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 141: flag=_wrap_IndexVector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 142: flag=_wrap_IndexVector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 143: flag=_wrap_IndexVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 144: flag=_wrap_IndexVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 145: flag=_wrap_delete_IndexVector(resc,resv,argc,(mxArray**)(argv)); break; + case 146: flag=_wrap_BerdySensors_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 147: flag=_wrap_BerdySensors_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 148: flag=_wrap_BerdySensors_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 149: flag=_wrap_BerdySensors_append(resc,resv,argc,(mxArray**)(argv)); break; + case 150: flag=_wrap_BerdySensors_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 151: flag=_wrap_BerdySensors_size(resc,resv,argc,(mxArray**)(argv)); break; + case 152: flag=_wrap_BerdySensors_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 153: flag=_wrap_BerdySensors_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 154: flag=_wrap_BerdySensors_end(resc,resv,argc,(mxArray**)(argv)); break; + case 155: flag=_wrap_BerdySensors_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 156: flag=_wrap_BerdySensors_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 157: flag=_wrap_BerdySensors_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 158: flag=_wrap_BerdySensors_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 159: flag=_wrap_BerdySensors_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 160: flag=_wrap_BerdySensors_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 161: flag=_wrap_new_BerdySensors(resc,resv,argc,(mxArray**)(argv)); break; + case 162: flag=_wrap_BerdySensors_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 163: flag=_wrap_BerdySensors_front(resc,resv,argc,(mxArray**)(argv)); break; + case 164: flag=_wrap_BerdySensors_back(resc,resv,argc,(mxArray**)(argv)); break; + case 165: flag=_wrap_BerdySensors_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 166: flag=_wrap_BerdySensors_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 167: flag=_wrap_BerdySensors_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 168: flag=_wrap_BerdySensors_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 169: flag=_wrap_BerdySensors_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 170: flag=_wrap_delete_BerdySensors(resc,resv,argc,(mxArray**)(argv)); break; + case 171: flag=_wrap_BerdyDynamicVariables_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 172: flag=_wrap_BerdyDynamicVariables_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 173: flag=_wrap_BerdyDynamicVariables_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 174: flag=_wrap_BerdyDynamicVariables_append(resc,resv,argc,(mxArray**)(argv)); break; + case 175: flag=_wrap_BerdyDynamicVariables_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 176: flag=_wrap_BerdyDynamicVariables_size(resc,resv,argc,(mxArray**)(argv)); break; + case 177: flag=_wrap_BerdyDynamicVariables_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 178: flag=_wrap_BerdyDynamicVariables_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 179: flag=_wrap_BerdyDynamicVariables_end(resc,resv,argc,(mxArray**)(argv)); break; + case 180: flag=_wrap_BerdyDynamicVariables_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 181: flag=_wrap_BerdyDynamicVariables_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 182: flag=_wrap_BerdyDynamicVariables_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 183: flag=_wrap_BerdyDynamicVariables_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 184: flag=_wrap_BerdyDynamicVariables_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 185: flag=_wrap_BerdyDynamicVariables_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 186: flag=_wrap_new_BerdyDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 187: flag=_wrap_BerdyDynamicVariables_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 188: flag=_wrap_BerdyDynamicVariables_front(resc,resv,argc,(mxArray**)(argv)); break; + case 189: flag=_wrap_BerdyDynamicVariables_back(resc,resv,argc,(mxArray**)(argv)); break; + case 190: flag=_wrap_BerdyDynamicVariables_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 191: flag=_wrap_BerdyDynamicVariables_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 192: flag=_wrap_BerdyDynamicVariables_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 193: flag=_wrap_BerdyDynamicVariables_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 194: flag=_wrap_BerdyDynamicVariables_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 195: flag=_wrap_delete_BerdyDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 196: flag=_wrap_reportInfo(resc,resv,argc,(mxArray**)(argv)); break; + case 197: flag=_wrap_reportDebug(resc,resv,argc,(mxArray**)(argv)); break; + case 198: flag=_wrap_IndexRange_offset_get(resc,resv,argc,(mxArray**)(argv)); break; + case 199: flag=_wrap_IndexRange_offset_set(resc,resv,argc,(mxArray**)(argv)); break; + case 200: flag=_wrap_IndexRange_size_get(resc,resv,argc,(mxArray**)(argv)); break; + case 201: flag=_wrap_IndexRange_size_set(resc,resv,argc,(mxArray**)(argv)); break; + case 202: flag=_wrap_IndexRange_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 203: flag=_wrap_IndexRange_InvalidRange(resc,resv,argc,(mxArray**)(argv)); break; + case 204: flag=_wrap_new_IndexRange(resc,resv,argc,(mxArray**)(argv)); break; + case 205: flag=_wrap_delete_IndexRange(resc,resv,argc,(mxArray**)(argv)); break; + case 206: flag=_wrap_checkDoublesAreEqual(resc,resv,argc,(mxArray**)(argv)); break; + case 207: flag=_wrap_new_MatrixDynSize(resc,resv,argc,(mxArray**)(argv)); break; + case 208: flag=_wrap_delete_MatrixDynSize(resc,resv,argc,(mxArray**)(argv)); break; + case 209: flag=_wrap_MatrixDynSize_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 210: flag=_wrap_MatrixDynSize_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 211: flag=_wrap_MatrixDynSize_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 212: flag=_wrap_MatrixDynSize_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 213: flag=_wrap_MatrixDynSize_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 214: flag=_wrap_MatrixDynSize_data(resc,resv,argc,(mxArray**)(argv)); break; + case 215: flag=_wrap_MatrixDynSize_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 216: flag=_wrap_MatrixDynSize_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 217: flag=_wrap_MatrixDynSize_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 218: flag=_wrap_MatrixDynSize_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 219: flag=_wrap_MatrixDynSize_shrink_to_fit(resc,resv,argc,(mxArray**)(argv)); break; + case 220: flag=_wrap_MatrixDynSize_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 221: flag=_wrap_MatrixDynSize_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 222: flag=_wrap_MatrixDynSize_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 223: flag=_wrap_MatrixDynSize_display(resc,resv,argc,(mxArray**)(argv)); break; + case 224: flag=_wrap_MatrixDynSize_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 225: flag=_wrap_MatrixDynSize_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 226: flag=_wrap_new_SparseMatrixRowMajor(resc,resv,argc,(mxArray**)(argv)); break; + case 227: flag=_wrap_delete_SparseMatrixRowMajor(resc,resv,argc,(mxArray**)(argv)); break; + case 228: flag=_wrap_SparseMatrixRowMajor_numberOfNonZeros(resc,resv,argc,(mxArray**)(argv)); break; + case 229: flag=_wrap_SparseMatrixRowMajor_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 230: flag=_wrap_SparseMatrixRowMajor_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 231: flag=_wrap_SparseMatrixRowMajor_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 232: flag=_wrap_SparseMatrixRowMajor_setFromConstTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 233: flag=_wrap_SparseMatrixRowMajor_setFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 234: flag=_wrap_SparseMatrixRowMajor_sparseMatrixFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 235: flag=_wrap_SparseMatrixRowMajor_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 236: flag=_wrap_SparseMatrixRowMajor_getValue(resc,resv,argc,(mxArray**)(argv)); break; + case 237: flag=_wrap_SparseMatrixRowMajor_setValue(resc,resv,argc,(mxArray**)(argv)); break; + case 238: flag=_wrap_SparseMatrixRowMajor_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 239: flag=_wrap_SparseMatrixRowMajor_columns(resc,resv,argc,(mxArray**)(argv)); break; + case 240: flag=_wrap_SparseMatrixRowMajor_description(resc,resv,argc,(mxArray**)(argv)); break; + case 241: flag=_wrap_SparseMatrixRowMajor_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 242: flag=_wrap_SparseMatrixRowMajor_toMatlabDense(resc,resv,argc,(mxArray**)(argv)); break; + case 243: flag=_wrap_SparseMatrixRowMajor_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 244: flag=_wrap_new_SparseMatrixColMajor(resc,resv,argc,(mxArray**)(argv)); break; + case 245: flag=_wrap_delete_SparseMatrixColMajor(resc,resv,argc,(mxArray**)(argv)); break; + case 246: flag=_wrap_SparseMatrixColMajor_numberOfNonZeros(resc,resv,argc,(mxArray**)(argv)); break; + case 247: flag=_wrap_SparseMatrixColMajor_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 248: flag=_wrap_SparseMatrixColMajor_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 249: flag=_wrap_SparseMatrixColMajor_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 250: flag=_wrap_SparseMatrixColMajor_setFromConstTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 251: flag=_wrap_SparseMatrixColMajor_setFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 252: flag=_wrap_SparseMatrixColMajor_sparseMatrixFromTriplets(resc,resv,argc,(mxArray**)(argv)); break; + case 253: flag=_wrap_SparseMatrixColMajor_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 254: flag=_wrap_SparseMatrixColMajor_getValue(resc,resv,argc,(mxArray**)(argv)); break; + case 255: flag=_wrap_SparseMatrixColMajor_setValue(resc,resv,argc,(mxArray**)(argv)); break; + case 256: flag=_wrap_SparseMatrixColMajor_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 257: flag=_wrap_SparseMatrixColMajor_columns(resc,resv,argc,(mxArray**)(argv)); break; + case 258: flag=_wrap_SparseMatrixColMajor_description(resc,resv,argc,(mxArray**)(argv)); break; + case 259: flag=_wrap_SparseMatrixColMajor_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 260: flag=_wrap_SparseMatrixColMajor_toMatlabDense(resc,resv,argc,(mxArray**)(argv)); break; + case 261: flag=_wrap_SparseMatrixColMajor_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 262: flag=_wrap_new_VectorDynSize(resc,resv,argc,(mxArray**)(argv)); break; + case 263: flag=_wrap_delete_VectorDynSize(resc,resv,argc,(mxArray**)(argv)); break; + case 264: flag=_wrap_VectorDynSize_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 265: flag=_wrap_VectorDynSize_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 266: flag=_wrap_VectorDynSize_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 267: flag=_wrap_VectorDynSize_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 268: flag=_wrap_VectorDynSize_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 269: flag=_wrap_VectorDynSize_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 270: flag=_wrap_VectorDynSize_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 271: flag=_wrap_VectorDynSize_end(resc,resv,argc,(mxArray**)(argv)); break; + case 272: flag=_wrap_VectorDynSize_size(resc,resv,argc,(mxArray**)(argv)); break; + case 273: flag=_wrap_VectorDynSize_data(resc,resv,argc,(mxArray**)(argv)); break; + case 274: flag=_wrap_VectorDynSize_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 275: flag=_wrap_VectorDynSize_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 276: flag=_wrap_VectorDynSize_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 277: flag=_wrap_VectorDynSize_shrink_to_fit(resc,resv,argc,(mxArray**)(argv)); break; + case 278: flag=_wrap_VectorDynSize_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 279: flag=_wrap_VectorDynSize_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 280: flag=_wrap_VectorDynSize_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 281: flag=_wrap_VectorDynSize_display(resc,resv,argc,(mxArray**)(argv)); break; + case 282: flag=_wrap_VectorDynSize_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 283: flag=_wrap_VectorDynSize_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 284: flag=_wrap_new_Matrix1x6(resc,resv,argc,(mxArray**)(argv)); break; + case 285: flag=_wrap_Matrix1x6_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 286: flag=_wrap_Matrix1x6_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 287: flag=_wrap_Matrix1x6_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 288: flag=_wrap_Matrix1x6_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 289: flag=_wrap_Matrix1x6_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 290: flag=_wrap_Matrix1x6_data(resc,resv,argc,(mxArray**)(argv)); break; + case 291: flag=_wrap_Matrix1x6_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 292: flag=_wrap_Matrix1x6_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 293: flag=_wrap_Matrix1x6_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 294: flag=_wrap_Matrix1x6_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 295: flag=_wrap_Matrix1x6_display(resc,resv,argc,(mxArray**)(argv)); break; + case 296: flag=_wrap_Matrix1x6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 297: flag=_wrap_Matrix1x6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 298: flag=_wrap_delete_Matrix1x6(resc,resv,argc,(mxArray**)(argv)); break; + case 299: flag=_wrap_new_Matrix2x3(resc,resv,argc,(mxArray**)(argv)); break; + case 300: flag=_wrap_Matrix2x3_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 301: flag=_wrap_Matrix2x3_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 302: flag=_wrap_Matrix2x3_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 303: flag=_wrap_Matrix2x3_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 304: flag=_wrap_Matrix2x3_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 305: flag=_wrap_Matrix2x3_data(resc,resv,argc,(mxArray**)(argv)); break; + case 306: flag=_wrap_Matrix2x3_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 307: flag=_wrap_Matrix2x3_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 308: flag=_wrap_Matrix2x3_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 309: flag=_wrap_Matrix2x3_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 310: flag=_wrap_Matrix2x3_display(resc,resv,argc,(mxArray**)(argv)); break; + case 311: flag=_wrap_Matrix2x3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 312: flag=_wrap_Matrix2x3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 313: flag=_wrap_delete_Matrix2x3(resc,resv,argc,(mxArray**)(argv)); break; + case 314: flag=_wrap_new_Matrix3x3(resc,resv,argc,(mxArray**)(argv)); break; + case 315: flag=_wrap_Matrix3x3_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 316: flag=_wrap_Matrix3x3_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 317: flag=_wrap_Matrix3x3_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 318: flag=_wrap_Matrix3x3_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 319: flag=_wrap_Matrix3x3_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 320: flag=_wrap_Matrix3x3_data(resc,resv,argc,(mxArray**)(argv)); break; + case 321: flag=_wrap_Matrix3x3_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 322: flag=_wrap_Matrix3x3_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 323: flag=_wrap_Matrix3x3_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 324: flag=_wrap_Matrix3x3_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 325: flag=_wrap_Matrix3x3_display(resc,resv,argc,(mxArray**)(argv)); break; + case 326: flag=_wrap_Matrix3x3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 327: flag=_wrap_Matrix3x3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 328: flag=_wrap_delete_Matrix3x3(resc,resv,argc,(mxArray**)(argv)); break; + case 329: flag=_wrap_new_Matrix4x4(resc,resv,argc,(mxArray**)(argv)); break; + case 330: flag=_wrap_Matrix4x4_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 331: flag=_wrap_Matrix4x4_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 332: flag=_wrap_Matrix4x4_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 333: flag=_wrap_Matrix4x4_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 334: flag=_wrap_Matrix4x4_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 335: flag=_wrap_Matrix4x4_data(resc,resv,argc,(mxArray**)(argv)); break; + case 336: flag=_wrap_Matrix4x4_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 337: flag=_wrap_Matrix4x4_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 338: flag=_wrap_Matrix4x4_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 339: flag=_wrap_Matrix4x4_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 340: flag=_wrap_Matrix4x4_display(resc,resv,argc,(mxArray**)(argv)); break; + case 341: flag=_wrap_Matrix4x4_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 342: flag=_wrap_Matrix4x4_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 343: flag=_wrap_delete_Matrix4x4(resc,resv,argc,(mxArray**)(argv)); break; + case 344: flag=_wrap_new_Matrix6x6(resc,resv,argc,(mxArray**)(argv)); break; + case 345: flag=_wrap_Matrix6x6_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 346: flag=_wrap_Matrix6x6_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 347: flag=_wrap_Matrix6x6_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 348: flag=_wrap_Matrix6x6_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 349: flag=_wrap_Matrix6x6_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 350: flag=_wrap_Matrix6x6_data(resc,resv,argc,(mxArray**)(argv)); break; + case 351: flag=_wrap_Matrix6x6_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 352: flag=_wrap_Matrix6x6_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 353: flag=_wrap_Matrix6x6_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 354: flag=_wrap_Matrix6x6_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 355: flag=_wrap_Matrix6x6_display(resc,resv,argc,(mxArray**)(argv)); break; + case 356: flag=_wrap_Matrix6x6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 357: flag=_wrap_Matrix6x6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 358: flag=_wrap_delete_Matrix6x6(resc,resv,argc,(mxArray**)(argv)); break; + case 359: flag=_wrap_new_Matrix6x10(resc,resv,argc,(mxArray**)(argv)); break; + case 360: flag=_wrap_Matrix6x10_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 361: flag=_wrap_Matrix6x10_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 362: flag=_wrap_Matrix6x10_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 363: flag=_wrap_Matrix6x10_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 364: flag=_wrap_Matrix6x10_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 365: flag=_wrap_Matrix6x10_data(resc,resv,argc,(mxArray**)(argv)); break; + case 366: flag=_wrap_Matrix6x10_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 367: flag=_wrap_Matrix6x10_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 368: flag=_wrap_Matrix6x10_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 369: flag=_wrap_Matrix6x10_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 370: flag=_wrap_Matrix6x10_display(resc,resv,argc,(mxArray**)(argv)); break; + case 371: flag=_wrap_Matrix6x10_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 372: flag=_wrap_Matrix6x10_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 373: flag=_wrap_delete_Matrix6x10(resc,resv,argc,(mxArray**)(argv)); break; + case 374: flag=_wrap_new_Matrix10x16(resc,resv,argc,(mxArray**)(argv)); break; + case 375: flag=_wrap_Matrix10x16_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 376: flag=_wrap_Matrix10x16_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 377: flag=_wrap_Matrix10x16_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 378: flag=_wrap_Matrix10x16_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 379: flag=_wrap_Matrix10x16_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 380: flag=_wrap_Matrix10x16_data(resc,resv,argc,(mxArray**)(argv)); break; + case 381: flag=_wrap_Matrix10x16_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 382: flag=_wrap_Matrix10x16_fillRowMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 383: flag=_wrap_Matrix10x16_fillColMajorBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 384: flag=_wrap_Matrix10x16_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 385: flag=_wrap_Matrix10x16_display(resc,resv,argc,(mxArray**)(argv)); break; + case 386: flag=_wrap_Matrix10x16_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 387: flag=_wrap_Matrix10x16_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 388: flag=_wrap_delete_Matrix10x16(resc,resv,argc,(mxArray**)(argv)); break; + case 389: flag=_wrap_new_Vector3(resc,resv,argc,(mxArray**)(argv)); break; + case 390: flag=_wrap_Vector3_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 391: flag=_wrap_Vector3_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 392: flag=_wrap_Vector3_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 393: flag=_wrap_Vector3_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 394: flag=_wrap_Vector3_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 395: flag=_wrap_Vector3_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 396: flag=_wrap_Vector3_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 397: flag=_wrap_Vector3_end(resc,resv,argc,(mxArray**)(argv)); break; + case 398: flag=_wrap_Vector3_size(resc,resv,argc,(mxArray**)(argv)); break; + case 399: flag=_wrap_Vector3_data(resc,resv,argc,(mxArray**)(argv)); break; + case 400: flag=_wrap_Vector3_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 401: flag=_wrap_Vector3_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 402: flag=_wrap_Vector3_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 403: flag=_wrap_Vector3_display(resc,resv,argc,(mxArray**)(argv)); break; + case 404: flag=_wrap_Vector3_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 405: flag=_wrap_Vector3_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 406: flag=_wrap_delete_Vector3(resc,resv,argc,(mxArray**)(argv)); break; + case 407: flag=_wrap_new_Vector4(resc,resv,argc,(mxArray**)(argv)); break; + case 408: flag=_wrap_Vector4_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 409: flag=_wrap_Vector4_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 410: flag=_wrap_Vector4_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 411: flag=_wrap_Vector4_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 412: flag=_wrap_Vector4_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 413: flag=_wrap_Vector4_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 414: flag=_wrap_Vector4_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 415: flag=_wrap_Vector4_end(resc,resv,argc,(mxArray**)(argv)); break; + case 416: flag=_wrap_Vector4_size(resc,resv,argc,(mxArray**)(argv)); break; + case 417: flag=_wrap_Vector4_data(resc,resv,argc,(mxArray**)(argv)); break; + case 418: flag=_wrap_Vector4_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 419: flag=_wrap_Vector4_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 420: flag=_wrap_Vector4_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 421: flag=_wrap_Vector4_display(resc,resv,argc,(mxArray**)(argv)); break; + case 422: flag=_wrap_Vector4_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 423: flag=_wrap_Vector4_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 424: flag=_wrap_delete_Vector4(resc,resv,argc,(mxArray**)(argv)); break; + case 425: flag=_wrap_new_Vector6(resc,resv,argc,(mxArray**)(argv)); break; + case 426: flag=_wrap_Vector6_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 427: flag=_wrap_Vector6_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 428: flag=_wrap_Vector6_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 429: flag=_wrap_Vector6_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 430: flag=_wrap_Vector6_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 431: flag=_wrap_Vector6_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 432: flag=_wrap_Vector6_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 433: flag=_wrap_Vector6_end(resc,resv,argc,(mxArray**)(argv)); break; + case 434: flag=_wrap_Vector6_size(resc,resv,argc,(mxArray**)(argv)); break; + case 435: flag=_wrap_Vector6_data(resc,resv,argc,(mxArray**)(argv)); break; + case 436: flag=_wrap_Vector6_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 437: flag=_wrap_Vector6_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 438: flag=_wrap_Vector6_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 439: flag=_wrap_Vector6_display(resc,resv,argc,(mxArray**)(argv)); break; + case 440: flag=_wrap_Vector6_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 441: flag=_wrap_Vector6_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 442: flag=_wrap_delete_Vector6(resc,resv,argc,(mxArray**)(argv)); break; + case 443: flag=_wrap_new_Vector10(resc,resv,argc,(mxArray**)(argv)); break; + case 444: flag=_wrap_Vector10_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 445: flag=_wrap_Vector10_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 446: flag=_wrap_Vector10_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 447: flag=_wrap_Vector10_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 448: flag=_wrap_Vector10_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 449: flag=_wrap_Vector10_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 450: flag=_wrap_Vector10_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 451: flag=_wrap_Vector10_end(resc,resv,argc,(mxArray**)(argv)); break; + case 452: flag=_wrap_Vector10_size(resc,resv,argc,(mxArray**)(argv)); break; + case 453: flag=_wrap_Vector10_data(resc,resv,argc,(mxArray**)(argv)); break; + case 454: flag=_wrap_Vector10_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 455: flag=_wrap_Vector10_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 456: flag=_wrap_Vector10_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 457: flag=_wrap_Vector10_display(resc,resv,argc,(mxArray**)(argv)); break; + case 458: flag=_wrap_Vector10_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 459: flag=_wrap_Vector10_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 460: flag=_wrap_delete_Vector10(resc,resv,argc,(mxArray**)(argv)); break; + case 461: flag=_wrap_new_Vector16(resc,resv,argc,(mxArray**)(argv)); break; + case 462: flag=_wrap_Vector16_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 463: flag=_wrap_Vector16_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 464: flag=_wrap_Vector16_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 465: flag=_wrap_Vector16_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 466: flag=_wrap_Vector16_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 467: flag=_wrap_Vector16_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 468: flag=_wrap_Vector16_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 469: flag=_wrap_Vector16_end(resc,resv,argc,(mxArray**)(argv)); break; + case 470: flag=_wrap_Vector16_size(resc,resv,argc,(mxArray**)(argv)); break; + case 471: flag=_wrap_Vector16_data(resc,resv,argc,(mxArray**)(argv)); break; + case 472: flag=_wrap_Vector16_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 473: flag=_wrap_Vector16_fillBuffer(resc,resv,argc,(mxArray**)(argv)); break; + case 474: flag=_wrap_Vector16_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 475: flag=_wrap_Vector16_display(resc,resv,argc,(mxArray**)(argv)); break; + case 476: flag=_wrap_Vector16_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 477: flag=_wrap_Vector16_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 478: flag=_wrap_delete_Vector16(resc,resv,argc,(mxArray**)(argv)); break; + case 479: flag=_wrap_new_Position(resc,resv,argc,(mxArray**)(argv)); break; + case 480: flag=_wrap_Position_changePoint(resc,resv,argc,(mxArray**)(argv)); break; + case 481: flag=_wrap_Position_changeRefPoint(resc,resv,argc,(mxArray**)(argv)); break; + case 482: flag=_wrap_Position_changeCoordinateFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 483: flag=_wrap_Position_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 484: flag=_wrap_Position_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 485: flag=_wrap_Position_changePointOf(resc,resv,argc,(mxArray**)(argv)); break; + case 486: flag=_wrap_Position_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 487: flag=_wrap_Position_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 488: flag=_wrap_Position_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 489: flag=_wrap_Position_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 490: flag=_wrap_Position_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 491: flag=_wrap_Position_display(resc,resv,argc,(mxArray**)(argv)); break; + case 492: flag=_wrap_Position_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 493: flag=_wrap_delete_Position(resc,resv,argc,(mxArray**)(argv)); break; + case 494: flag=_wrap_new_GeomVector3(resc,resv,argc,(mxArray**)(argv)); break; + case 495: flag=_wrap_GeomVector3_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 496: flag=_wrap_GeomVector3_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 497: flag=_wrap_GeomVector3_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 498: flag=_wrap_GeomVector3_dot(resc,resv,argc,(mxArray**)(argv)); break; + case 499: flag=_wrap_GeomVector3_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 500: flag=_wrap_GeomVector3_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 501: flag=_wrap_GeomVector3_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 502: flag=_wrap_GeomVector3_exp(resc,resv,argc,(mxArray**)(argv)); break; + case 503: flag=_wrap_GeomVector3_cross(resc,resv,argc,(mxArray**)(argv)); break; + case 504: flag=_wrap_delete_GeomVector3(resc,resv,argc,(mxArray**)(argv)); break; + case 505: flag=_wrap_new_SpatialMotionVectorBase(resc,resv,argc,(mxArray**)(argv)); break; + case 506: flag=_wrap_SpatialMotionVectorBase_getLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 507: flag=_wrap_SpatialMotionVectorBase_getAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 508: flag=_wrap_SpatialMotionVectorBase_setLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 509: flag=_wrap_SpatialMotionVectorBase_setAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 510: flag=_wrap_SpatialMotionVectorBase_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 511: flag=_wrap_SpatialMotionVectorBase_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 512: flag=_wrap_SpatialMotionVectorBase_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 513: flag=_wrap_SpatialMotionVectorBase_size(resc,resv,argc,(mxArray**)(argv)); break; + case 514: flag=_wrap_SpatialMotionVectorBase_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 515: flag=_wrap_SpatialMotionVectorBase_changePoint(resc,resv,argc,(mxArray**)(argv)); break; + case 516: flag=_wrap_SpatialMotionVectorBase_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 517: flag=_wrap_SpatialMotionVectorBase_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 518: flag=_wrap_SpatialMotionVectorBase_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 519: flag=_wrap_SpatialMotionVectorBase_dot(resc,resv,argc,(mxArray**)(argv)); break; + case 520: flag=_wrap_SpatialMotionVectorBase_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 521: flag=_wrap_SpatialMotionVectorBase_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 522: flag=_wrap_SpatialMotionVectorBase_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 523: flag=_wrap_SpatialMotionVectorBase_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 524: flag=_wrap_SpatialMotionVectorBase_asVector(resc,resv,argc,(mxArray**)(argv)); break; + case 525: flag=_wrap_SpatialMotionVectorBase_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 526: flag=_wrap_SpatialMotionVectorBase_display(resc,resv,argc,(mxArray**)(argv)); break; + case 527: flag=_wrap_SpatialMotionVectorBase_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 528: flag=_wrap_SpatialMotionVectorBase_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 529: flag=_wrap_delete_SpatialMotionVectorBase(resc,resv,argc,(mxArray**)(argv)); break; + case 530: flag=_wrap_new_SpatialForceVectorBase(resc,resv,argc,(mxArray**)(argv)); break; + case 531: flag=_wrap_SpatialForceVectorBase_getLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 532: flag=_wrap_SpatialForceVectorBase_getAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 533: flag=_wrap_SpatialForceVectorBase_setLinearVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 534: flag=_wrap_SpatialForceVectorBase_setAngularVec3(resc,resv,argc,(mxArray**)(argv)); break; + case 535: flag=_wrap_SpatialForceVectorBase_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 536: flag=_wrap_SpatialForceVectorBase_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 537: flag=_wrap_SpatialForceVectorBase_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 538: flag=_wrap_SpatialForceVectorBase_size(resc,resv,argc,(mxArray**)(argv)); break; + case 539: flag=_wrap_SpatialForceVectorBase_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 540: flag=_wrap_SpatialForceVectorBase_changePoint(resc,resv,argc,(mxArray**)(argv)); break; + case 541: flag=_wrap_SpatialForceVectorBase_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 542: flag=_wrap_SpatialForceVectorBase_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 543: flag=_wrap_SpatialForceVectorBase_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 544: flag=_wrap_SpatialForceVectorBase_dot(resc,resv,argc,(mxArray**)(argv)); break; + case 545: flag=_wrap_SpatialForceVectorBase_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 546: flag=_wrap_SpatialForceVectorBase_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 547: flag=_wrap_SpatialForceVectorBase_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 548: flag=_wrap_SpatialForceVectorBase_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 549: flag=_wrap_SpatialForceVectorBase_asVector(resc,resv,argc,(mxArray**)(argv)); break; + case 550: flag=_wrap_SpatialForceVectorBase_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 551: flag=_wrap_SpatialForceVectorBase_display(resc,resv,argc,(mxArray**)(argv)); break; + case 552: flag=_wrap_SpatialForceVectorBase_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 553: flag=_wrap_SpatialForceVectorBase_fromMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 554: flag=_wrap_delete_SpatialForceVectorBase(resc,resv,argc,(mxArray**)(argv)); break; + case 555: flag=_wrap_new_Dummy(resc,resv,argc,(mxArray**)(argv)); break; + case 556: flag=_wrap_delete_Dummy(resc,resv,argc,(mxArray**)(argv)); break; + case 557: flag=_wrap_new_SpatialMotionVector(resc,resv,argc,(mxArray**)(argv)); break; + case 558: flag=_wrap_SpatialMotionVector_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 559: flag=_wrap_SpatialMotionVector_cross(resc,resv,argc,(mxArray**)(argv)); break; + case 560: flag=_wrap_SpatialMotionVector_asCrossProductMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 561: flag=_wrap_SpatialMotionVector_asCrossProductMatrixWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 562: flag=_wrap_SpatialMotionVector_exp(resc,resv,argc,(mxArray**)(argv)); break; + case 563: flag=_wrap_delete_SpatialMotionVector(resc,resv,argc,(mxArray**)(argv)); break; + case 564: flag=_wrap_new_SpatialForceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 565: flag=_wrap_delete_SpatialForceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 566: flag=_wrap_SpatialForceVector_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 567: flag=_wrap_new_Twist(resc,resv,argc,(mxArray**)(argv)); break; + case 568: flag=_wrap_Twist_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 569: flag=_wrap_Twist_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 570: flag=_wrap_Twist_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 571: flag=_wrap_Twist_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 572: flag=_wrap_delete_Twist(resc,resv,argc,(mxArray**)(argv)); break; + case 573: flag=_wrap_new_Wrench(resc,resv,argc,(mxArray**)(argv)); break; + case 574: flag=_wrap_Wrench_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 575: flag=_wrap_Wrench_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 576: flag=_wrap_Wrench_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 577: flag=_wrap_delete_Wrench(resc,resv,argc,(mxArray**)(argv)); break; + case 578: flag=_wrap_new_SpatialMomentum(resc,resv,argc,(mxArray**)(argv)); break; + case 579: flag=_wrap_SpatialMomentum_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 580: flag=_wrap_SpatialMomentum_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 581: flag=_wrap_SpatialMomentum_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 582: flag=_wrap_delete_SpatialMomentum(resc,resv,argc,(mxArray**)(argv)); break; + case 583: flag=_wrap_new_SpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 584: flag=_wrap_SpatialAcc_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 585: flag=_wrap_SpatialAcc_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 586: flag=_wrap_SpatialAcc_uminus(resc,resv,argc,(mxArray**)(argv)); break; + case 587: flag=_wrap_delete_SpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 588: flag=_wrap_new_ClassicalAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 589: flag=_wrap_ClassicalAcc_changeCoordFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 590: flag=_wrap_ClassicalAcc_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 591: flag=_wrap_ClassicalAcc_fromSpatial(resc,resv,argc,(mxArray**)(argv)); break; + case 592: flag=_wrap_ClassicalAcc_toSpatial(resc,resv,argc,(mxArray**)(argv)); break; + case 593: flag=_wrap_delete_ClassicalAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 594: flag=_wrap_new_Direction(resc,resv,argc,(mxArray**)(argv)); break; + case 595: flag=_wrap_Direction_Normalize(resc,resv,argc,(mxArray**)(argv)); break; + case 596: flag=_wrap_Direction_isParallel(resc,resv,argc,(mxArray**)(argv)); break; + case 597: flag=_wrap_Direction_isPerpendicular(resc,resv,argc,(mxArray**)(argv)); break; + case 598: flag=_wrap_Direction_reverse(resc,resv,argc,(mxArray**)(argv)); break; + case 599: flag=_wrap_Direction_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 600: flag=_wrap_Direction_display(resc,resv,argc,(mxArray**)(argv)); break; + case 601: flag=_wrap_Direction_Default(resc,resv,argc,(mxArray**)(argv)); break; + case 602: flag=_wrap_delete_Direction(resc,resv,argc,(mxArray**)(argv)); break; + case 603: flag=_wrap_new_Axis(resc,resv,argc,(mxArray**)(argv)); break; + case 604: flag=_wrap_Axis_getDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 605: flag=_wrap_Axis_getOrigin(resc,resv,argc,(mxArray**)(argv)); break; + case 606: flag=_wrap_Axis_setDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 607: flag=_wrap_Axis_setOrigin(resc,resv,argc,(mxArray**)(argv)); break; + case 608: flag=_wrap_Axis_getRotationTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 609: flag=_wrap_Axis_getRotationTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 610: flag=_wrap_Axis_getRotationTwist(resc,resv,argc,(mxArray**)(argv)); break; + case 611: flag=_wrap_Axis_getRotationSpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 612: flag=_wrap_Axis_getTranslationTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 613: flag=_wrap_Axis_getTranslationTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 614: flag=_wrap_Axis_getTranslationTwist(resc,resv,argc,(mxArray**)(argv)); break; + case 615: flag=_wrap_Axis_getTranslationSpatialAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 616: flag=_wrap_Axis_isParallel(resc,resv,argc,(mxArray**)(argv)); break; + case 617: flag=_wrap_Axis_reverse(resc,resv,argc,(mxArray**)(argv)); break; + case 618: flag=_wrap_Axis_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 619: flag=_wrap_Axis_display(resc,resv,argc,(mxArray**)(argv)); break; + case 620: flag=_wrap_delete_Axis(resc,resv,argc,(mxArray**)(argv)); break; + case 621: flag=_wrap_new_RotationalInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 622: flag=_wrap_RotationalInertia_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 623: flag=_wrap_delete_RotationalInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 624: flag=_wrap_new_SpatialInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 625: flag=_wrap_SpatialInertia_combine(resc,resv,argc,(mxArray**)(argv)); break; + case 626: flag=_wrap_SpatialInertia_fromRotationalInertiaWrtCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; + case 627: flag=_wrap_SpatialInertia_getMass(resc,resv,argc,(mxArray**)(argv)); break; + case 628: flag=_wrap_SpatialInertia_getCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; + case 629: flag=_wrap_SpatialInertia_getRotationalInertiaWrtFrameOrigin(resc,resv,argc,(mxArray**)(argv)); break; + case 630: flag=_wrap_SpatialInertia_getRotationalInertiaWrtCenterOfMass(resc,resv,argc,(mxArray**)(argv)); break; + case 631: flag=_wrap_SpatialInertia_multiply(resc,resv,argc,(mxArray**)(argv)); break; + case 632: flag=_wrap_SpatialInertia_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 633: flag=_wrap_SpatialInertia_asMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 634: flag=_wrap_SpatialInertia_applyInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 635: flag=_wrap_SpatialInertia_getInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 636: flag=_wrap_SpatialInertia_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 637: flag=_wrap_SpatialInertia_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 638: flag=_wrap_SpatialInertia_biasWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 639: flag=_wrap_SpatialInertia_biasWrenchDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 640: flag=_wrap_SpatialInertia_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 641: flag=_wrap_SpatialInertia_asVector(resc,resv,argc,(mxArray**)(argv)); break; + case 642: flag=_wrap_SpatialInertia_fromVector(resc,resv,argc,(mxArray**)(argv)); break; + case 643: flag=_wrap_SpatialInertia_isPhysicallyConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 644: flag=_wrap_SpatialInertia_momentumRegressor(resc,resv,argc,(mxArray**)(argv)); break; + case 645: flag=_wrap_SpatialInertia_momentumDerivativeRegressor(resc,resv,argc,(mxArray**)(argv)); break; + case 646: flag=_wrap_SpatialInertia_momentumDerivativeSlotineLiRegressor(resc,resv,argc,(mxArray**)(argv)); break; + case 647: flag=_wrap_delete_SpatialInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 648: flag=_wrap_new_ArticulatedBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 649: flag=_wrap_ArticulatedBodyInertia_getLinearLinearSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 650: flag=_wrap_ArticulatedBodyInertia_getLinearAngularSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 651: flag=_wrap_ArticulatedBodyInertia_getAngularAngularSubmatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 652: flag=_wrap_ArticulatedBodyInertia_combine(resc,resv,argc,(mxArray**)(argv)); break; + case 653: flag=_wrap_ArticulatedBodyInertia_applyInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 654: flag=_wrap_ArticulatedBodyInertia_asMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 655: flag=_wrap_ArticulatedBodyInertia_getInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 656: flag=_wrap_ArticulatedBodyInertia_plus(resc,resv,argc,(mxArray**)(argv)); break; + case 657: flag=_wrap_ArticulatedBodyInertia_minus(resc,resv,argc,(mxArray**)(argv)); break; + case 658: flag=_wrap_ArticulatedBodyInertia_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 659: flag=_wrap_ArticulatedBodyInertia_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 660: flag=_wrap_ArticulatedBodyInertia_ABADyadHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 661: flag=_wrap_ArticulatedBodyInertia_ABADyadHelperLin(resc,resv,argc,(mxArray**)(argv)); break; + case 662: flag=_wrap_delete_ArticulatedBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 663: flag=_wrap_RigidBodyInertiaNonLinearParametrization_mass_get(resc,resv,argc,(mxArray**)(argv)); break; + case 664: flag=_wrap_RigidBodyInertiaNonLinearParametrization_mass_set(resc,resv,argc,(mxArray**)(argv)); break; + case 665: flag=_wrap_RigidBodyInertiaNonLinearParametrization_com_get(resc,resv,argc,(mxArray**)(argv)); break; + case 666: flag=_wrap_RigidBodyInertiaNonLinearParametrization_com_set(resc,resv,argc,(mxArray**)(argv)); break; + case 667: flag=_wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_get(resc,resv,argc,(mxArray**)(argv)); break; + case 668: flag=_wrap_RigidBodyInertiaNonLinearParametrization_link_R_centroidal_set(resc,resv,argc,(mxArray**)(argv)); break; + case 669: flag=_wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_get(resc,resv,argc,(mxArray**)(argv)); break; + case 670: flag=_wrap_RigidBodyInertiaNonLinearParametrization_centralSecondMomentOfMass_set(resc,resv,argc,(mxArray**)(argv)); break; + case 671: flag=_wrap_RigidBodyInertiaNonLinearParametrization_getLinkCentroidalTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 672: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromRigidBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 673: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 674: flag=_wrap_RigidBodyInertiaNonLinearParametrization_toRigidBodyInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 675: flag=_wrap_RigidBodyInertiaNonLinearParametrization_isPhysicallyConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 676: flag=_wrap_RigidBodyInertiaNonLinearParametrization_asVectorWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; + case 677: flag=_wrap_RigidBodyInertiaNonLinearParametrization_fromVectorWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; + case 678: flag=_wrap_RigidBodyInertiaNonLinearParametrization_getGradientWithRotationAsVec(resc,resv,argc,(mxArray**)(argv)); break; + case 679: flag=_wrap_new_RigidBodyInertiaNonLinearParametrization(resc,resv,argc,(mxArray**)(argv)); break; + case 680: flag=_wrap_delete_RigidBodyInertiaNonLinearParametrization(resc,resv,argc,(mxArray**)(argv)); break; + case 681: flag=_wrap_new_Rotation(resc,resv,argc,(mxArray**)(argv)); break; + case 682: flag=_wrap_Rotation_changeOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 683: flag=_wrap_Rotation_changeRefOrientFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 684: flag=_wrap_Rotation_changeCoordinateFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 685: flag=_wrap_Rotation_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 686: flag=_wrap_Rotation_inverse2(resc,resv,argc,(mxArray**)(argv)); break; + case 687: flag=_wrap_Rotation_changeCoordFrameOf(resc,resv,argc,(mxArray**)(argv)); break; + case 688: flag=_wrap_Rotation_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 689: flag=_wrap_Rotation_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 690: flag=_wrap_Rotation_log(resc,resv,argc,(mxArray**)(argv)); break; + case 691: flag=_wrap_Rotation_fromQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 692: flag=_wrap_Rotation_getRPY(resc,resv,argc,(mxArray**)(argv)); break; + case 693: flag=_wrap_Rotation_asRPY(resc,resv,argc,(mxArray**)(argv)); break; + case 694: flag=_wrap_Rotation_getQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 695: flag=_wrap_Rotation_asQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 696: flag=_wrap_Rotation_RotX(resc,resv,argc,(mxArray**)(argv)); break; + case 697: flag=_wrap_Rotation_RotY(resc,resv,argc,(mxArray**)(argv)); break; + case 698: flag=_wrap_Rotation_RotZ(resc,resv,argc,(mxArray**)(argv)); break; + case 699: flag=_wrap_Rotation_RotAxis(resc,resv,argc,(mxArray**)(argv)); break; + case 700: flag=_wrap_Rotation_RotAxisDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 701: flag=_wrap_Rotation_RPY(resc,resv,argc,(mxArray**)(argv)); break; + case 702: flag=_wrap_Rotation_RPYRightTrivializedDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 703: flag=_wrap_Rotation_RPYRightTrivializedDerivativeRateOfChange(resc,resv,argc,(mxArray**)(argv)); break; + case 704: flag=_wrap_Rotation_RPYRightTrivializedDerivativeInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 705: flag=_wrap_Rotation_RPYRightTrivializedDerivativeInverseRateOfChange(resc,resv,argc,(mxArray**)(argv)); break; + case 706: flag=_wrap_Rotation_QuaternionRightTrivializedDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 707: flag=_wrap_Rotation_QuaternionRightTrivializedDerivativeInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 708: flag=_wrap_Rotation_Identity(resc,resv,argc,(mxArray**)(argv)); break; + case 709: flag=_wrap_Rotation_RotationFromQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 710: flag=_wrap_Rotation_leftJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 711: flag=_wrap_Rotation_leftJacobianInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 712: flag=_wrap_Rotation_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 713: flag=_wrap_Rotation_display(resc,resv,argc,(mxArray**)(argv)); break; + case 714: flag=_wrap_delete_Rotation(resc,resv,argc,(mxArray**)(argv)); break; + case 715: flag=_wrap_new_Transform(resc,resv,argc,(mxArray**)(argv)); break; + case 716: flag=_wrap_Transform_fromHomogeneousTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 717: flag=_wrap_Transform_getRotation(resc,resv,argc,(mxArray**)(argv)); break; + case 718: flag=_wrap_Transform_getPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 719: flag=_wrap_Transform_setRotation(resc,resv,argc,(mxArray**)(argv)); break; + case 720: flag=_wrap_Transform_setPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 721: flag=_wrap_Transform_compose(resc,resv,argc,(mxArray**)(argv)); break; + case 722: flag=_wrap_Transform_inverse2(resc,resv,argc,(mxArray**)(argv)); break; + case 723: flag=_wrap_Transform_inverse(resc,resv,argc,(mxArray**)(argv)); break; + case 724: flag=_wrap_Transform_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 725: flag=_wrap_Transform_Identity(resc,resv,argc,(mxArray**)(argv)); break; + case 726: flag=_wrap_Transform_asHomogeneousTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 727: flag=_wrap_Transform_asAdjointTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 728: flag=_wrap_Transform_asAdjointTransformWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 729: flag=_wrap_Transform_log(resc,resv,argc,(mxArray**)(argv)); break; + case 730: flag=_wrap_Transform_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 731: flag=_wrap_Transform_display(resc,resv,argc,(mxArray**)(argv)); break; + case 732: flag=_wrap_delete_Transform(resc,resv,argc,(mxArray**)(argv)); break; + case 733: flag=_wrap_new_TransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 734: flag=_wrap_delete_TransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 735: flag=_wrap_TransformDerivative_getRotationDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 736: flag=_wrap_TransformDerivative_getPositionDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 737: flag=_wrap_TransformDerivative_setRotationDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 738: flag=_wrap_TransformDerivative_setPositionDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 739: flag=_wrap_TransformDerivative_Zero(resc,resv,argc,(mxArray**)(argv)); break; + case 740: flag=_wrap_TransformDerivative_asHomogeneousTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 741: flag=_wrap_TransformDerivative_asAdjointTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 742: flag=_wrap_TransformDerivative_asAdjointTransformWrenchDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 743: flag=_wrap_TransformDerivative_mtimes(resc,resv,argc,(mxArray**)(argv)); break; + case 744: flag=_wrap_TransformDerivative_derivativeOfInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 745: flag=_wrap_TransformDerivative_transform(resc,resv,argc,(mxArray**)(argv)); break; + case 746: flag=_wrap_dynamic_extent_get(resc,resv,argc,(mxArray**)(argv)); break; + case 747: flag=_wrap_DynamicSpan_extent_get(resc,resv,argc,(mxArray**)(argv)); break; + case 748: flag=_wrap_new_DynamicSpan(resc,resv,argc,(mxArray**)(argv)); break; + case 749: flag=_wrap_delete_DynamicSpan(resc,resv,argc,(mxArray**)(argv)); break; + case 750: flag=_wrap_DynamicSpan_first(resc,resv,argc,(mxArray**)(argv)); break; + case 751: flag=_wrap_DynamicSpan_last(resc,resv,argc,(mxArray**)(argv)); break; + case 752: flag=_wrap_DynamicSpan_subspan(resc,resv,argc,(mxArray**)(argv)); break; + case 753: flag=_wrap_DynamicSpan_size(resc,resv,argc,(mxArray**)(argv)); break; + case 754: flag=_wrap_DynamicSpan_size_bytes(resc,resv,argc,(mxArray**)(argv)); break; + case 755: flag=_wrap_DynamicSpan_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 756: flag=_wrap_DynamicSpan_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 757: flag=_wrap_DynamicSpan_getVal(resc,resv,argc,(mxArray**)(argv)); break; + case 758: flag=_wrap_DynamicSpan_setVal(resc,resv,argc,(mxArray**)(argv)); break; + case 759: flag=_wrap_DynamicSpan_at(resc,resv,argc,(mxArray**)(argv)); break; + case 760: flag=_wrap_DynamicSpan_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 761: flag=_wrap_DynamicSpan_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 762: flag=_wrap_DynamicSpan_end(resc,resv,argc,(mxArray**)(argv)); break; + case 763: flag=_wrap_DynamicSpan_cbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 764: flag=_wrap_DynamicSpan_cend(resc,resv,argc,(mxArray**)(argv)); break; + case 765: flag=_wrap_DynamicSpan_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 766: flag=_wrap_DynamicSpan_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 767: flag=_wrap_DynamicSpan_crbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 768: flag=_wrap_DynamicSpan_crend(resc,resv,argc,(mxArray**)(argv)); break; + case 769: flag=_wrap_new_DynamicMatrixView(resc,resv,argc,(mxArray**)(argv)); break; + case 770: flag=_wrap_DynamicMatrixView_storageOrder(resc,resv,argc,(mxArray**)(argv)); break; + case 771: flag=_wrap_DynamicMatrixView_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 772: flag=_wrap_DynamicMatrixView_rows(resc,resv,argc,(mxArray**)(argv)); break; + case 773: flag=_wrap_DynamicMatrixView_cols(resc,resv,argc,(mxArray**)(argv)); break; + case 774: flag=_wrap_DynamicMatrixView_block(resc,resv,argc,(mxArray**)(argv)); break; + case 775: flag=_wrap_delete_DynamicMatrixView(resc,resv,argc,(mxArray**)(argv)); break; + case 776: flag=_wrap_LINK_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; + case 777: flag=_wrap_LINK_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; + case 778: flag=_wrap_LINK_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; + case 779: flag=_wrap_LINK_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; + case 780: flag=_wrap_JOINT_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; + case 781: flag=_wrap_JOINT_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; + case 782: flag=_wrap_JOINT_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; + case 783: flag=_wrap_JOINT_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; + case 784: flag=_wrap_DOF_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; + case 785: flag=_wrap_DOF_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; + case 786: flag=_wrap_DOF_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; + case 787: flag=_wrap_DOF_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; + case 788: flag=_wrap_FRAME_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; + case 789: flag=_wrap_FRAME_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; + case 790: flag=_wrap_FRAME_INVALID_NAME_get(resc,resv,argc,(mxArray**)(argv)); break; + case 791: flag=_wrap_FRAME_INVALID_NAME_set(resc,resv,argc,(mxArray**)(argv)); break; + case 792: flag=_wrap_TRAVERSAL_INVALID_INDEX_get(resc,resv,argc,(mxArray**)(argv)); break; + case 793: flag=_wrap_TRAVERSAL_INVALID_INDEX_set(resc,resv,argc,(mxArray**)(argv)); break; + case 794: flag=_wrap_new_LinkPositions(resc,resv,argc,(mxArray**)(argv)); break; + case 795: flag=_wrap_LinkPositions_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 796: flag=_wrap_LinkPositions_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 797: flag=_wrap_LinkPositions_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 798: flag=_wrap_LinkPositions_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 799: flag=_wrap_LinkPositions_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 800: flag=_wrap_delete_LinkPositions(resc,resv,argc,(mxArray**)(argv)); break; + case 801: flag=_wrap_new_LinkWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 802: flag=_wrap_LinkWrenches_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 803: flag=_wrap_LinkWrenches_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 804: flag=_wrap_LinkWrenches_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 805: flag=_wrap_LinkWrenches_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 806: flag=_wrap_LinkWrenches_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 807: flag=_wrap_LinkWrenches_zero(resc,resv,argc,(mxArray**)(argv)); break; + case 808: flag=_wrap_delete_LinkWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 809: flag=_wrap_new_LinkInertias(resc,resv,argc,(mxArray**)(argv)); break; + case 810: flag=_wrap_LinkInertias_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 811: flag=_wrap_LinkInertias_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 812: flag=_wrap_LinkInertias_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 813: flag=_wrap_delete_LinkInertias(resc,resv,argc,(mxArray**)(argv)); break; + case 814: flag=_wrap_new_LinkArticulatedBodyInertias(resc,resv,argc,(mxArray**)(argv)); break; + case 815: flag=_wrap_LinkArticulatedBodyInertias_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 816: flag=_wrap_LinkArticulatedBodyInertias_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 817: flag=_wrap_LinkArticulatedBodyInertias_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 818: flag=_wrap_delete_LinkArticulatedBodyInertias(resc,resv,argc,(mxArray**)(argv)); break; + case 819: flag=_wrap_new_LinkVelArray(resc,resv,argc,(mxArray**)(argv)); break; + case 820: flag=_wrap_LinkVelArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 821: flag=_wrap_LinkVelArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 822: flag=_wrap_LinkVelArray_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 823: flag=_wrap_LinkVelArray_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 824: flag=_wrap_LinkVelArray_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 825: flag=_wrap_delete_LinkVelArray(resc,resv,argc,(mxArray**)(argv)); break; + case 826: flag=_wrap_new_LinkAccArray(resc,resv,argc,(mxArray**)(argv)); break; + case 827: flag=_wrap_LinkAccArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 828: flag=_wrap_LinkAccArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 829: flag=_wrap_LinkAccArray_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 830: flag=_wrap_LinkAccArray_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 831: flag=_wrap_LinkAccArray_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 832: flag=_wrap_delete_LinkAccArray(resc,resv,argc,(mxArray**)(argv)); break; + case 833: flag=_wrap_new_Link(resc,resv,argc,(mxArray**)(argv)); break; + case 834: flag=_wrap_Link_inertia(resc,resv,argc,(mxArray**)(argv)); break; + case 835: flag=_wrap_Link_setInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 836: flag=_wrap_Link_getInertia(resc,resv,argc,(mxArray**)(argv)); break; + case 837: flag=_wrap_Link_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 838: flag=_wrap_Link_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 839: flag=_wrap_delete_Link(resc,resv,argc,(mxArray**)(argv)); break; + case 840: flag=_wrap_delete_IJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 841: flag=_wrap_IJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 842: flag=_wrap_IJoint_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 843: flag=_wrap_IJoint_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 844: flag=_wrap_IJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 845: flag=_wrap_IJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 846: flag=_wrap_IJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 847: flag=_wrap_IJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 848: flag=_wrap_IJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 849: flag=_wrap_IJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 850: flag=_wrap_IJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 851: flag=_wrap_IJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 852: flag=_wrap_IJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 853: flag=_wrap_IJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 854: flag=_wrap_IJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; + case 855: flag=_wrap_IJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 856: flag=_wrap_IJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 857: flag=_wrap_IJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; + case 858: flag=_wrap_IJoint_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 859: flag=_wrap_IJoint_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 860: flag=_wrap_IJoint_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 861: flag=_wrap_IJoint_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 862: flag=_wrap_IJoint_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 863: flag=_wrap_IJoint_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 864: flag=_wrap_IJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 865: flag=_wrap_IJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 866: flag=_wrap_IJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 867: flag=_wrap_IJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 868: flag=_wrap_IJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 869: flag=_wrap_IJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 870: flag=_wrap_IJoint_getJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 871: flag=_wrap_IJoint_setJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 872: flag=_wrap_IJoint_setDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 873: flag=_wrap_IJoint_setStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 874: flag=_wrap_IJoint_getDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 875: flag=_wrap_IJoint_getStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 876: flag=_wrap_IJoint_isRevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 877: flag=_wrap_IJoint_isFixedJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 878: flag=_wrap_IJoint_isPrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 879: flag=_wrap_IJoint_asRevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 880: flag=_wrap_IJoint_asFixedJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 881: flag=_wrap_IJoint_asPrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 882: flag=_wrap_new_FixedJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 883: flag=_wrap_delete_FixedJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 884: flag=_wrap_FixedJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 885: flag=_wrap_FixedJoint_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 886: flag=_wrap_FixedJoint_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 887: flag=_wrap_FixedJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 888: flag=_wrap_FixedJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 889: flag=_wrap_FixedJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 890: flag=_wrap_FixedJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 891: flag=_wrap_FixedJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 892: flag=_wrap_FixedJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 893: flag=_wrap_FixedJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 894: flag=_wrap_FixedJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 895: flag=_wrap_FixedJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 896: flag=_wrap_FixedJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 897: flag=_wrap_FixedJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; + case 898: flag=_wrap_FixedJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 899: flag=_wrap_FixedJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 900: flag=_wrap_FixedJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; + case 901: flag=_wrap_FixedJoint_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 902: flag=_wrap_FixedJoint_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 903: flag=_wrap_FixedJoint_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 904: flag=_wrap_FixedJoint_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 905: flag=_wrap_FixedJoint_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 906: flag=_wrap_FixedJoint_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 907: flag=_wrap_FixedJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 908: flag=_wrap_FixedJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 909: flag=_wrap_FixedJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 910: flag=_wrap_FixedJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 911: flag=_wrap_FixedJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 912: flag=_wrap_FixedJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 913: flag=_wrap_FixedJoint_getJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 914: flag=_wrap_FixedJoint_setJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 915: flag=_wrap_FixedJoint_getDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 916: flag=_wrap_FixedJoint_getStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 917: flag=_wrap_FixedJoint_setDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 918: flag=_wrap_FixedJoint_setStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 919: flag=_wrap_delete_MovableJointImpl1(resc,resv,argc,(mxArray**)(argv)); break; + case 920: flag=_wrap_MovableJointImpl1_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 921: flag=_wrap_MovableJointImpl1_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 922: flag=_wrap_MovableJointImpl1_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 923: flag=_wrap_MovableJointImpl1_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 924: flag=_wrap_MovableJointImpl1_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 925: flag=_wrap_MovableJointImpl1_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 926: flag=_wrap_MovableJointImpl1_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 927: flag=_wrap_MovableJointImpl1_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 928: flag=_wrap_delete_MovableJointImpl2(resc,resv,argc,(mxArray**)(argv)); break; + case 929: flag=_wrap_MovableJointImpl2_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 930: flag=_wrap_MovableJointImpl2_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 931: flag=_wrap_MovableJointImpl2_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 932: flag=_wrap_MovableJointImpl2_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 933: flag=_wrap_MovableJointImpl2_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 934: flag=_wrap_MovableJointImpl2_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 935: flag=_wrap_MovableJointImpl2_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 936: flag=_wrap_MovableJointImpl2_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 937: flag=_wrap_delete_MovableJointImpl3(resc,resv,argc,(mxArray**)(argv)); break; + case 938: flag=_wrap_MovableJointImpl3_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 939: flag=_wrap_MovableJointImpl3_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 940: flag=_wrap_MovableJointImpl3_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 941: flag=_wrap_MovableJointImpl3_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 942: flag=_wrap_MovableJointImpl3_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 943: flag=_wrap_MovableJointImpl3_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 944: flag=_wrap_MovableJointImpl3_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 945: flag=_wrap_MovableJointImpl3_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 946: flag=_wrap_delete_MovableJointImpl4(resc,resv,argc,(mxArray**)(argv)); break; + case 947: flag=_wrap_MovableJointImpl4_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 948: flag=_wrap_MovableJointImpl4_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 949: flag=_wrap_MovableJointImpl4_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 950: flag=_wrap_MovableJointImpl4_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 951: flag=_wrap_MovableJointImpl4_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 952: flag=_wrap_MovableJointImpl4_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 953: flag=_wrap_MovableJointImpl4_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 954: flag=_wrap_MovableJointImpl4_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 955: flag=_wrap_delete_MovableJointImpl5(resc,resv,argc,(mxArray**)(argv)); break; + case 956: flag=_wrap_MovableJointImpl5_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 957: flag=_wrap_MovableJointImpl5_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 958: flag=_wrap_MovableJointImpl5_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 959: flag=_wrap_MovableJointImpl5_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 960: flag=_wrap_MovableJointImpl5_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 961: flag=_wrap_MovableJointImpl5_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 962: flag=_wrap_MovableJointImpl5_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 963: flag=_wrap_MovableJointImpl5_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 964: flag=_wrap_delete_MovableJointImpl6(resc,resv,argc,(mxArray**)(argv)); break; + case 965: flag=_wrap_MovableJointImpl6_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 966: flag=_wrap_MovableJointImpl6_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 967: flag=_wrap_MovableJointImpl6_setIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 968: flag=_wrap_MovableJointImpl6_getIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 969: flag=_wrap_MovableJointImpl6_setPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 970: flag=_wrap_MovableJointImpl6_getPosCoordsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 971: flag=_wrap_MovableJointImpl6_setDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 972: flag=_wrap_MovableJointImpl6_getDOFsOffset(resc,resv,argc,(mxArray**)(argv)); break; + case 973: flag=_wrap_new_RevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 974: flag=_wrap_delete_RevoluteJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 975: flag=_wrap_RevoluteJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 976: flag=_wrap_RevoluteJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 977: flag=_wrap_RevoluteJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 978: flag=_wrap_RevoluteJoint_setAxis(resc,resv,argc,(mxArray**)(argv)); break; + case 979: flag=_wrap_RevoluteJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 980: flag=_wrap_RevoluteJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 981: flag=_wrap_RevoluteJoint_getAxis(resc,resv,argc,(mxArray**)(argv)); break; + case 982: flag=_wrap_RevoluteJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 983: flag=_wrap_RevoluteJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 984: flag=_wrap_RevoluteJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 985: flag=_wrap_RevoluteJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 986: flag=_wrap_RevoluteJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 987: flag=_wrap_RevoluteJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; + case 988: flag=_wrap_RevoluteJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 989: flag=_wrap_RevoluteJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 990: flag=_wrap_RevoluteJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 991: flag=_wrap_RevoluteJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; + case 992: flag=_wrap_RevoluteJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 993: flag=_wrap_RevoluteJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 994: flag=_wrap_RevoluteJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 995: flag=_wrap_RevoluteJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 996: flag=_wrap_RevoluteJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 997: flag=_wrap_RevoluteJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 998: flag=_wrap_RevoluteJoint_getJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 999: flag=_wrap_RevoluteJoint_setJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 1000: flag=_wrap_RevoluteJoint_getDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 1001: flag=_wrap_RevoluteJoint_getStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 1002: flag=_wrap_RevoluteJoint_setDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 1003: flag=_wrap_RevoluteJoint_setStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 1004: flag=_wrap_new_PrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1005: flag=_wrap_delete_PrismaticJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1006: flag=_wrap_PrismaticJoint_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1007: flag=_wrap_PrismaticJoint_setAttachedLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1008: flag=_wrap_PrismaticJoint_setRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1009: flag=_wrap_PrismaticJoint_setAxis(resc,resv,argc,(mxArray**)(argv)); break; + case 1010: flag=_wrap_PrismaticJoint_getFirstAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1011: flag=_wrap_PrismaticJoint_getSecondAttachedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1012: flag=_wrap_PrismaticJoint_getAxis(resc,resv,argc,(mxArray**)(argv)); break; + case 1013: flag=_wrap_PrismaticJoint_getRestTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1014: flag=_wrap_PrismaticJoint_getTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1015: flag=_wrap_PrismaticJoint_getTransformDerivative(resc,resv,argc,(mxArray**)(argv)); break; + case 1016: flag=_wrap_PrismaticJoint_getMotionSubspaceVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1017: flag=_wrap_PrismaticJoint_computeChildPosVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1018: flag=_wrap_PrismaticJoint_computeChildVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1019: flag=_wrap_PrismaticJoint_computeChildVelAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1020: flag=_wrap_PrismaticJoint_computeChildAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1021: flag=_wrap_PrismaticJoint_computeChildBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1022: flag=_wrap_PrismaticJoint_computeJointTorque(resc,resv,argc,(mxArray**)(argv)); break; + case 1023: flag=_wrap_PrismaticJoint_hasPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 1024: flag=_wrap_PrismaticJoint_enablePosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 1025: flag=_wrap_PrismaticJoint_getPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 1026: flag=_wrap_PrismaticJoint_getMinPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 1027: flag=_wrap_PrismaticJoint_getMaxPosLimit(resc,resv,argc,(mxArray**)(argv)); break; + case 1028: flag=_wrap_PrismaticJoint_setPosLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 1029: flag=_wrap_PrismaticJoint_getJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 1030: flag=_wrap_PrismaticJoint_setJointDynamicsType(resc,resv,argc,(mxArray**)(argv)); break; + case 1031: flag=_wrap_PrismaticJoint_getDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 1032: flag=_wrap_PrismaticJoint_getStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 1033: flag=_wrap_PrismaticJoint_setDamping(resc,resv,argc,(mxArray**)(argv)); break; + case 1034: flag=_wrap_PrismaticJoint_setStaticFriction(resc,resv,argc,(mxArray**)(argv)); break; + case 1035: flag=_wrap_new_Traversal(resc,resv,argc,(mxArray**)(argv)); break; + case 1036: flag=_wrap_delete_Traversal(resc,resv,argc,(mxArray**)(argv)); break; + case 1037: flag=_wrap_Traversal_getNrOfVisitedLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1038: flag=_wrap_Traversal_getLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1039: flag=_wrap_Traversal_getBaseLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1040: flag=_wrap_Traversal_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1041: flag=_wrap_Traversal_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1042: flag=_wrap_Traversal_getParentLinkFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1043: flag=_wrap_Traversal_getParentJointFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1044: flag=_wrap_Traversal_getTraversalIndexFromLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1045: flag=_wrap_Traversal_reset(resc,resv,argc,(mxArray**)(argv)); break; + case 1046: flag=_wrap_Traversal_addTraversalBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1047: flag=_wrap_Traversal_addTraversalElement(resc,resv,argc,(mxArray**)(argv)); break; + case 1048: flag=_wrap_Traversal_isParentOf(resc,resv,argc,(mxArray**)(argv)); break; + case 1049: flag=_wrap_Traversal_getChildLinkIndexFromJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1050: flag=_wrap_Traversal_getParentLinkIndexFromJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1051: flag=_wrap_Traversal_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 1052: flag=_wrap_new_Material(resc,resv,argc,(mxArray**)(argv)); break; + case 1053: flag=_wrap_Material_name(resc,resv,argc,(mxArray**)(argv)); break; + case 1054: flag=_wrap_Material_hasColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1055: flag=_wrap_Material_color(resc,resv,argc,(mxArray**)(argv)); break; + case 1056: flag=_wrap_Material_setColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1057: flag=_wrap_Material_hasTexture(resc,resv,argc,(mxArray**)(argv)); break; + case 1058: flag=_wrap_Material_texture(resc,resv,argc,(mxArray**)(argv)); break; + case 1059: flag=_wrap_Material_setTexture(resc,resv,argc,(mxArray**)(argv)); break; + case 1060: flag=_wrap_delete_Material(resc,resv,argc,(mxArray**)(argv)); break; + case 1061: flag=_wrap_delete_SolidShape(resc,resv,argc,(mxArray**)(argv)); break; + case 1062: flag=_wrap_SolidShape_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1063: flag=_wrap_SolidShape_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1064: flag=_wrap_SolidShape_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1065: flag=_wrap_SolidShape_isNameValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1066: flag=_wrap_SolidShape_getLink_H_geometry(resc,resv,argc,(mxArray**)(argv)); break; + case 1067: flag=_wrap_SolidShape_setLink_H_geometry(resc,resv,argc,(mxArray**)(argv)); break; + case 1068: flag=_wrap_SolidShape_isMaterialSet(resc,resv,argc,(mxArray**)(argv)); break; + case 1069: flag=_wrap_SolidShape_getMaterial(resc,resv,argc,(mxArray**)(argv)); break; + case 1070: flag=_wrap_SolidShape_setMaterial(resc,resv,argc,(mxArray**)(argv)); break; + case 1071: flag=_wrap_SolidShape_isSphere(resc,resv,argc,(mxArray**)(argv)); break; + case 1072: flag=_wrap_SolidShape_isBox(resc,resv,argc,(mxArray**)(argv)); break; + case 1073: flag=_wrap_SolidShape_isCylinder(resc,resv,argc,(mxArray**)(argv)); break; + case 1074: flag=_wrap_SolidShape_isExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; + case 1075: flag=_wrap_SolidShape_asSphere(resc,resv,argc,(mxArray**)(argv)); break; + case 1076: flag=_wrap_SolidShape_asBox(resc,resv,argc,(mxArray**)(argv)); break; + case 1077: flag=_wrap_SolidShape_asCylinder(resc,resv,argc,(mxArray**)(argv)); break; + case 1078: flag=_wrap_SolidShape_asExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; + case 1079: flag=_wrap_delete_Sphere(resc,resv,argc,(mxArray**)(argv)); break; + case 1080: flag=_wrap_Sphere_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1081: flag=_wrap_Sphere_getRadius(resc,resv,argc,(mxArray**)(argv)); break; + case 1082: flag=_wrap_Sphere_setRadius(resc,resv,argc,(mxArray**)(argv)); break; + case 1083: flag=_wrap_new_Sphere(resc,resv,argc,(mxArray**)(argv)); break; + case 1084: flag=_wrap_delete_Box(resc,resv,argc,(mxArray**)(argv)); break; + case 1085: flag=_wrap_Box_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1086: flag=_wrap_Box_getX(resc,resv,argc,(mxArray**)(argv)); break; + case 1087: flag=_wrap_Box_setX(resc,resv,argc,(mxArray**)(argv)); break; + case 1088: flag=_wrap_Box_getY(resc,resv,argc,(mxArray**)(argv)); break; + case 1089: flag=_wrap_Box_setY(resc,resv,argc,(mxArray**)(argv)); break; + case 1090: flag=_wrap_Box_getZ(resc,resv,argc,(mxArray**)(argv)); break; + case 1091: flag=_wrap_Box_setZ(resc,resv,argc,(mxArray**)(argv)); break; + case 1092: flag=_wrap_new_Box(resc,resv,argc,(mxArray**)(argv)); break; + case 1093: flag=_wrap_delete_Cylinder(resc,resv,argc,(mxArray**)(argv)); break; + case 1094: flag=_wrap_Cylinder_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1095: flag=_wrap_Cylinder_getLength(resc,resv,argc,(mxArray**)(argv)); break; + case 1096: flag=_wrap_Cylinder_setLength(resc,resv,argc,(mxArray**)(argv)); break; + case 1097: flag=_wrap_Cylinder_getRadius(resc,resv,argc,(mxArray**)(argv)); break; + case 1098: flag=_wrap_Cylinder_setRadius(resc,resv,argc,(mxArray**)(argv)); break; + case 1099: flag=_wrap_new_Cylinder(resc,resv,argc,(mxArray**)(argv)); break; + case 1100: flag=_wrap_delete_ExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; + case 1101: flag=_wrap_ExternalMesh_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1102: flag=_wrap_ExternalMesh_getFilename(resc,resv,argc,(mxArray**)(argv)); break; + case 1103: flag=_wrap_ExternalMesh_getPackageDirs(resc,resv,argc,(mxArray**)(argv)); break; + case 1104: flag=_wrap_ExternalMesh_getFileLocationOnLocalFileSystem(resc,resv,argc,(mxArray**)(argv)); break; + case 1105: flag=_wrap_ExternalMesh_setFilename(resc,resv,argc,(mxArray**)(argv)); break; + case 1106: flag=_wrap_ExternalMesh_setPackageDirs(resc,resv,argc,(mxArray**)(argv)); break; + case 1107: flag=_wrap_ExternalMesh_getScale(resc,resv,argc,(mxArray**)(argv)); break; + case 1108: flag=_wrap_ExternalMesh_setScale(resc,resv,argc,(mxArray**)(argv)); break; + case 1109: flag=_wrap_new_ExternalMesh(resc,resv,argc,(mxArray**)(argv)); break; + case 1110: flag=_wrap_delete_ModelSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; + case 1111: flag=_wrap_new_ModelSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; + case 1112: flag=_wrap_ModelSolidShapes_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 1113: flag=_wrap_ModelSolidShapes_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1114: flag=_wrap_ModelSolidShapes_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1115: flag=_wrap_ModelSolidShapes_getLinkSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; + case 1116: flag=_wrap_NR_OF_SENSOR_TYPES_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1117: flag=_wrap_isLinkSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1118: flag=_wrap_isJointSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1119: flag=_wrap_getSensorTypeSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1120: flag=_wrap_delete_Sensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1121: flag=_wrap_Sensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1122: flag=_wrap_Sensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1123: flag=_wrap_Sensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1124: flag=_wrap_Sensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1125: flag=_wrap_Sensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1126: flag=_wrap_Sensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1127: flag=_wrap_Sensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1128: flag=_wrap_delete_JointSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1129: flag=_wrap_JointSensor_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1130: flag=_wrap_JointSensor_getParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1131: flag=_wrap_JointSensor_setParentJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1132: flag=_wrap_JointSensor_setParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1133: flag=_wrap_JointSensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1134: flag=_wrap_delete_LinkSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1135: flag=_wrap_LinkSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1136: flag=_wrap_LinkSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1137: flag=_wrap_LinkSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1138: flag=_wrap_LinkSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1139: flag=_wrap_LinkSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1140: flag=_wrap_LinkSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1141: flag=_wrap_LinkSensor_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1142: flag=_wrap_new_SensorsList(resc,resv,argc,(mxArray**)(argv)); break; + case 1143: flag=_wrap_delete_SensorsList(resc,resv,argc,(mxArray**)(argv)); break; + case 1144: flag=_wrap_SensorsList_addSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1145: flag=_wrap_SensorsList_setSerialization(resc,resv,argc,(mxArray**)(argv)); break; + case 1146: flag=_wrap_SensorsList_getSerialization(resc,resv,argc,(mxArray**)(argv)); break; + case 1147: flag=_wrap_SensorsList_getNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1148: flag=_wrap_SensorsList_getSensorIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1149: flag=_wrap_SensorsList_getSizeOfAllSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1150: flag=_wrap_SensorsList_getSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1151: flag=_wrap_SensorsList_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1152: flag=_wrap_SensorsList_removeSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1153: flag=_wrap_SensorsList_removeAllSensorsOfType(resc,resv,argc,(mxArray**)(argv)); break; + case 1154: flag=_wrap_SensorsList_getSixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1155: flag=_wrap_SensorsList_getAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1156: flag=_wrap_SensorsList_getGyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1157: flag=_wrap_SensorsList_getThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1158: flag=_wrap_SensorsList_getThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1159: flag=_wrap_new_SensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1160: flag=_wrap_delete_SensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1161: flag=_wrap_SensorsMeasurements_setNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1162: flag=_wrap_SensorsMeasurements_getNrOfSensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1163: flag=_wrap_SensorsMeasurements_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1164: flag=_wrap_SensorsMeasurements_toVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1165: flag=_wrap_SensorsMeasurements_setMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1166: flag=_wrap_SensorsMeasurements_getMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1167: flag=_wrap_SensorsMeasurements_getSizeOfAllSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1168: flag=_wrap_Neighbor_neighborLink_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1169: flag=_wrap_Neighbor_neighborLink_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1170: flag=_wrap_Neighbor_neighborJoint_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1171: flag=_wrap_Neighbor_neighborJoint_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1172: flag=_wrap_new_Neighbor(resc,resv,argc,(mxArray**)(argv)); break; + case 1173: flag=_wrap_delete_Neighbor(resc,resv,argc,(mxArray**)(argv)); break; + case 1174: flag=_wrap_new_Model(resc,resv,argc,(mxArray**)(argv)); break; + case 1175: flag=_wrap_Model_copy(resc,resv,argc,(mxArray**)(argv)); break; + case 1176: flag=_wrap_delete_Model(resc,resv,argc,(mxArray**)(argv)); break; + case 1177: flag=_wrap_Model_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1178: flag=_wrap_Model_getPackageDirs(resc,resv,argc,(mxArray**)(argv)); break; + case 1179: flag=_wrap_Model_setPackageDirs(resc,resv,argc,(mxArray**)(argv)); break; + case 1180: flag=_wrap_Model_getLinkName(resc,resv,argc,(mxArray**)(argv)); break; + case 1181: flag=_wrap_Model_getLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1182: flag=_wrap_Model_isValidLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1183: flag=_wrap_Model_getLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1184: flag=_wrap_Model_addLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1185: flag=_wrap_Model_getNrOfJoints(resc,resv,argc,(mxArray**)(argv)); break; + case 1186: flag=_wrap_Model_getJointName(resc,resv,argc,(mxArray**)(argv)); break; + case 1187: flag=_wrap_Model_getTotalMass(resc,resv,argc,(mxArray**)(argv)); break; + case 1188: flag=_wrap_Model_getJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1189: flag=_wrap_Model_getJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1190: flag=_wrap_Model_isValidJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1191: flag=_wrap_Model_isLinkNameUsed(resc,resv,argc,(mxArray**)(argv)); break; + case 1192: flag=_wrap_Model_isJointNameUsed(resc,resv,argc,(mxArray**)(argv)); break; + case 1193: flag=_wrap_Model_isFrameNameUsed(resc,resv,argc,(mxArray**)(argv)); break; + case 1194: flag=_wrap_Model_addJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1195: flag=_wrap_Model_addJointAndLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1196: flag=_wrap_Model_insertLinkToExistingJointAndAddJointForDisplacedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1197: flag=_wrap_Model_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 1198: flag=_wrap_Model_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1199: flag=_wrap_Model_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; + case 1200: flag=_wrap_Model_addAdditionalFrameToLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1201: flag=_wrap_Model_getFrameName(resc,resv,argc,(mxArray**)(argv)); break; + case 1202: flag=_wrap_Model_getFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1203: flag=_wrap_Model_isValidFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1204: flag=_wrap_Model_getFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1205: flag=_wrap_Model_getFrameLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1206: flag=_wrap_Model_getLinkAdditionalFrames(resc,resv,argc,(mxArray**)(argv)); break; + case 1207: flag=_wrap_Model_getNrOfNeighbors(resc,resv,argc,(mxArray**)(argv)); break; + case 1208: flag=_wrap_Model_getNeighbor(resc,resv,argc,(mxArray**)(argv)); break; + case 1209: flag=_wrap_Model_setDefaultBaseLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1210: flag=_wrap_Model_getDefaultBaseLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1211: flag=_wrap_Model_computeFullTreeTraversal(resc,resv,argc,(mxArray**)(argv)); break; + case 1212: flag=_wrap_Model_getInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1213: flag=_wrap_Model_updateInertialParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1214: flag=_wrap_Model_visualSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; + case 1215: flag=_wrap_Model_collisionSolidShapes(resc,resv,argc,(mxArray**)(argv)); break; + case 1216: flag=_wrap_Model_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1217: flag=_wrap_Model_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 1218: flag=_wrap_Model_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1219: flag=_wrap_new_JointPosDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1220: flag=_wrap_JointPosDoubleArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1221: flag=_wrap_JointPosDoubleArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1222: flag=_wrap_delete_JointPosDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1223: flag=_wrap_new_JointDOFsDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1224: flag=_wrap_JointDOFsDoubleArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1225: flag=_wrap_JointDOFsDoubleArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1226: flag=_wrap_delete_JointDOFsDoubleArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1227: flag=_wrap_new_DOFSpatialForceArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1228: flag=_wrap_DOFSpatialForceArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1229: flag=_wrap_DOFSpatialForceArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1230: flag=_wrap_DOFSpatialForceArray_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 1231: flag=_wrap_delete_DOFSpatialForceArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1232: flag=_wrap_new_DOFSpatialMotionArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1233: flag=_wrap_DOFSpatialMotionArray_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1234: flag=_wrap_DOFSpatialMotionArray_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1235: flag=_wrap_DOFSpatialMotionArray_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 1236: flag=_wrap_delete_DOFSpatialMotionArray(resc,resv,argc,(mxArray**)(argv)); break; + case 1237: flag=_wrap_new_FrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1238: flag=_wrap_FrameFreeFloatingJacobian_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1239: flag=_wrap_FrameFreeFloatingJacobian_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1240: flag=_wrap_delete_FrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1241: flag=_wrap_new_MomentumFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1242: flag=_wrap_MomentumFreeFloatingJacobian_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1243: flag=_wrap_MomentumFreeFloatingJacobian_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1244: flag=_wrap_delete_MomentumFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1245: flag=_wrap_new_FreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1246: flag=_wrap_FreeFloatingMassMatrix_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1247: flag=_wrap_delete_FreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1248: flag=_wrap_new_FreeFloatingPos(resc,resv,argc,(mxArray**)(argv)); break; + case 1249: flag=_wrap_FreeFloatingPos_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1250: flag=_wrap_FreeFloatingPos_worldBasePos(resc,resv,argc,(mxArray**)(argv)); break; + case 1251: flag=_wrap_FreeFloatingPos_jointPos(resc,resv,argc,(mxArray**)(argv)); break; + case 1252: flag=_wrap_FreeFloatingPos_getNrOfPosCoords(resc,resv,argc,(mxArray**)(argv)); break; + case 1253: flag=_wrap_delete_FreeFloatingPos(resc,resv,argc,(mxArray**)(argv)); break; + case 1254: flag=_wrap_new_FreeFloatingGeneralizedTorques(resc,resv,argc,(mxArray**)(argv)); break; + case 1255: flag=_wrap_FreeFloatingGeneralizedTorques_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1256: flag=_wrap_FreeFloatingGeneralizedTorques_baseWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1257: flag=_wrap_FreeFloatingGeneralizedTorques_jointTorques(resc,resv,argc,(mxArray**)(argv)); break; + case 1258: flag=_wrap_FreeFloatingGeneralizedTorques_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1259: flag=_wrap_delete_FreeFloatingGeneralizedTorques(resc,resv,argc,(mxArray**)(argv)); break; + case 1260: flag=_wrap_new_FreeFloatingVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1261: flag=_wrap_FreeFloatingVel_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1262: flag=_wrap_FreeFloatingVel_baseVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1263: flag=_wrap_FreeFloatingVel_jointVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1264: flag=_wrap_FreeFloatingVel_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1265: flag=_wrap_delete_FreeFloatingVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1266: flag=_wrap_new_FreeFloatingAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1267: flag=_wrap_FreeFloatingAcc_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1268: flag=_wrap_FreeFloatingAcc_baseAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1269: flag=_wrap_FreeFloatingAcc_jointAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1270: flag=_wrap_FreeFloatingAcc_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1271: flag=_wrap_delete_FreeFloatingAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1272: flag=_wrap_ContactWrench_contactId(resc,resv,argc,(mxArray**)(argv)); break; + case 1273: flag=_wrap_ContactWrench_contactPoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1274: flag=_wrap_ContactWrench_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1275: flag=_wrap_new_ContactWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1276: flag=_wrap_delete_ContactWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1277: flag=_wrap_new_LinkContactWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 1278: flag=_wrap_LinkContactWrenches_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1279: flag=_wrap_LinkContactWrenches_getNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1280: flag=_wrap_LinkContactWrenches_setNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1281: flag=_wrap_LinkContactWrenches_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1282: flag=_wrap_LinkContactWrenches_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1283: flag=_wrap_LinkContactWrenches_computeNetWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 1284: flag=_wrap_LinkContactWrenches_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 1285: flag=_wrap_delete_LinkContactWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 1286: flag=_wrap_getRandomLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1287: flag=_wrap_addRandomLinkToModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1288: flag=_wrap_addRandomAdditionalFrameToModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1289: flag=_wrap_getRandomLinkIndexOfModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1290: flag=_wrap_getRandomLinkOfModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1291: flag=_wrap_int2string(resc,resv,argc,(mxArray**)(argv)); break; + case 1292: flag=_wrap_getRandomModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1293: flag=_wrap_getRandomChain(resc,resv,argc,(mxArray**)(argv)); break; + case 1294: flag=_wrap_getRandomJointPositions(resc,resv,argc,(mxArray**)(argv)); break; + case 1295: flag=_wrap_getRandomInverseDynamicsInputs(resc,resv,argc,(mxArray**)(argv)); break; + case 1296: flag=_wrap_removeFakeLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1297: flag=_wrap_createReducedModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1298: flag=_wrap_createModelWithNormalizedJointNumbering(resc,resv,argc,(mxArray**)(argv)); break; + case 1299: flag=_wrap_extractSubModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1300: flag=_wrap_new_SubModelDecomposition(resc,resv,argc,(mxArray**)(argv)); break; + case 1301: flag=_wrap_delete_SubModelDecomposition(resc,resv,argc,(mxArray**)(argv)); break; + case 1302: flag=_wrap_SubModelDecomposition_splitModelAlongJoints(resc,resv,argc,(mxArray**)(argv)); break; + case 1303: flag=_wrap_SubModelDecomposition_setNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; + case 1304: flag=_wrap_SubModelDecomposition_getNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; + case 1305: flag=_wrap_SubModelDecomposition_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1306: flag=_wrap_SubModelDecomposition_getTraversal(resc,resv,argc,(mxArray**)(argv)); break; + case 1307: flag=_wrap_SubModelDecomposition_getSubModelOfLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1308: flag=_wrap_SubModelDecomposition_getSubModelOfFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 1309: flag=_wrap_computeTransformToTraversalBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1310: flag=_wrap_computeTransformToSubModelBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1311: flag=_wrap_new_SixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1312: flag=_wrap_delete_SixAxisForceTorqueSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1313: flag=_wrap_SixAxisForceTorqueSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1314: flag=_wrap_SixAxisForceTorqueSensor_setFirstLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1315: flag=_wrap_SixAxisForceTorqueSensor_setSecondLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1316: flag=_wrap_SixAxisForceTorqueSensor_getFirstLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1317: flag=_wrap_SixAxisForceTorqueSensor_getSecondLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1318: flag=_wrap_SixAxisForceTorqueSensor_setFirstLinkName(resc,resv,argc,(mxArray**)(argv)); break; + case 1319: flag=_wrap_SixAxisForceTorqueSensor_setSecondLinkName(resc,resv,argc,(mxArray**)(argv)); break; + case 1320: flag=_wrap_SixAxisForceTorqueSensor_getFirstLinkName(resc,resv,argc,(mxArray**)(argv)); break; + case 1321: flag=_wrap_SixAxisForceTorqueSensor_getSecondLinkName(resc,resv,argc,(mxArray**)(argv)); break; + case 1322: flag=_wrap_SixAxisForceTorqueSensor_setParentJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1323: flag=_wrap_SixAxisForceTorqueSensor_setParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1324: flag=_wrap_SixAxisForceTorqueSensor_setAppliedWrenchLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1325: flag=_wrap_SixAxisForceTorqueSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1326: flag=_wrap_SixAxisForceTorqueSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1327: flag=_wrap_SixAxisForceTorqueSensor_getParentJoint(resc,resv,argc,(mxArray**)(argv)); break; + case 1328: flag=_wrap_SixAxisForceTorqueSensor_getParentJointIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1329: flag=_wrap_SixAxisForceTorqueSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1330: flag=_wrap_SixAxisForceTorqueSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1331: flag=_wrap_SixAxisForceTorqueSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1332: flag=_wrap_SixAxisForceTorqueSensor_getAppliedWrenchLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1333: flag=_wrap_SixAxisForceTorqueSensor_isLinkAttachedToSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1334: flag=_wrap_SixAxisForceTorqueSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1335: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1336: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1337: flag=_wrap_SixAxisForceTorqueSensor_getWrenchAppliedOnLinkInverseMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1338: flag=_wrap_SixAxisForceTorqueSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1339: flag=_wrap_SixAxisForceTorqueSensor_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 1340: flag=_wrap_new_AccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1341: flag=_wrap_delete_AccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1342: flag=_wrap_AccelerometerSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1343: flag=_wrap_AccelerometerSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1344: flag=_wrap_AccelerometerSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1345: flag=_wrap_AccelerometerSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1346: flag=_wrap_AccelerometerSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1347: flag=_wrap_AccelerometerSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1348: flag=_wrap_AccelerometerSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1349: flag=_wrap_AccelerometerSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1350: flag=_wrap_AccelerometerSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1351: flag=_wrap_AccelerometerSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1352: flag=_wrap_AccelerometerSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1353: flag=_wrap_AccelerometerSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1354: flag=_wrap_AccelerometerSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1355: flag=_wrap_new_GyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1356: flag=_wrap_delete_GyroscopeSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1357: flag=_wrap_GyroscopeSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1358: flag=_wrap_GyroscopeSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1359: flag=_wrap_GyroscopeSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1360: flag=_wrap_GyroscopeSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1361: flag=_wrap_GyroscopeSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1362: flag=_wrap_GyroscopeSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1363: flag=_wrap_GyroscopeSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1364: flag=_wrap_GyroscopeSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1365: flag=_wrap_GyroscopeSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1366: flag=_wrap_GyroscopeSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1367: flag=_wrap_GyroscopeSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1368: flag=_wrap_GyroscopeSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1369: flag=_wrap_GyroscopeSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1370: flag=_wrap_new_ThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1371: flag=_wrap_delete_ThreeAxisAngularAccelerometerSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1372: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1373: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1374: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1375: flag=_wrap_ThreeAxisAngularAccelerometerSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1376: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1377: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1378: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1379: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1380: flag=_wrap_ThreeAxisAngularAccelerometerSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1381: flag=_wrap_ThreeAxisAngularAccelerometerSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1382: flag=_wrap_ThreeAxisAngularAccelerometerSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1383: flag=_wrap_ThreeAxisAngularAccelerometerSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1384: flag=_wrap_ThreeAxisAngularAccelerometerSensor_predictMeasurement(resc,resv,argc,(mxArray**)(argv)); break; + case 1385: flag=_wrap_new_ThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1386: flag=_wrap_delete_ThreeAxisForceTorqueContactSensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1387: flag=_wrap_ThreeAxisForceTorqueContactSensor_setName(resc,resv,argc,(mxArray**)(argv)); break; + case 1388: flag=_wrap_ThreeAxisForceTorqueContactSensor_setLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1389: flag=_wrap_ThreeAxisForceTorqueContactSensor_setParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1390: flag=_wrap_ThreeAxisForceTorqueContactSensor_setParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1391: flag=_wrap_ThreeAxisForceTorqueContactSensor_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1392: flag=_wrap_ThreeAxisForceTorqueContactSensor_getSensorType(resc,resv,argc,(mxArray**)(argv)); break; + case 1393: flag=_wrap_ThreeAxisForceTorqueContactSensor_getParentLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1394: flag=_wrap_ThreeAxisForceTorqueContactSensor_getParentLinkIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1395: flag=_wrap_ThreeAxisForceTorqueContactSensor_getLinkSensorTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1396: flag=_wrap_ThreeAxisForceTorqueContactSensor_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1397: flag=_wrap_ThreeAxisForceTorqueContactSensor_clone(resc,resv,argc,(mxArray**)(argv)); break; + case 1398: flag=_wrap_ThreeAxisForceTorqueContactSensor_updateIndices(resc,resv,argc,(mxArray**)(argv)); break; + case 1399: flag=_wrap_ThreeAxisForceTorqueContactSensor_setLoadCellLocations(resc,resv,argc,(mxArray**)(argv)); break; + case 1400: flag=_wrap_ThreeAxisForceTorqueContactSensor_getLoadCellLocations(resc,resv,argc,(mxArray**)(argv)); break; + case 1401: flag=_wrap_ThreeAxisForceTorqueContactSensor_computeThreeAxisForceTorqueFromLoadCellMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1402: flag=_wrap_ThreeAxisForceTorqueContactSensor_computeCenterOfPressureFromLoadCellMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1403: flag=_wrap_predictSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1404: flag=_wrap_predictSensorsMeasurementsFromRawBuffers(resc,resv,argc,(mxArray**)(argv)); break; + case 1405: flag=_wrap_SolidShapesVector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 1406: flag=_wrap_SolidShapesVector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 1407: flag=_wrap_SolidShapesVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 1408: flag=_wrap_SolidShapesVector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 1409: flag=_wrap_SolidShapesVector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 1410: flag=_wrap_SolidShapesVector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 1411: flag=_wrap_SolidShapesVector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 1412: flag=_wrap_SolidShapesVector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 1413: flag=_wrap_SolidShapesVector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 1414: flag=_wrap_SolidShapesVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 1415: flag=_wrap_SolidShapesVector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 1416: flag=_wrap_SolidShapesVector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 1417: flag=_wrap_SolidShapesVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 1418: flag=_wrap_SolidShapesVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1419: flag=_wrap_SolidShapesVector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 1420: flag=_wrap_new_SolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1421: flag=_wrap_SolidShapesVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1422: flag=_wrap_SolidShapesVector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 1423: flag=_wrap_SolidShapesVector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1424: flag=_wrap_SolidShapesVector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 1425: flag=_wrap_SolidShapesVector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1426: flag=_wrap_SolidShapesVector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 1427: flag=_wrap_SolidShapesVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 1428: flag=_wrap_SolidShapesVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 1429: flag=_wrap_delete_SolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1430: flag=_wrap_LinksSolidShapesVector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 1431: flag=_wrap_LinksSolidShapesVector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 1432: flag=_wrap_LinksSolidShapesVector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 1433: flag=_wrap_LinksSolidShapesVector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 1434: flag=_wrap_LinksSolidShapesVector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 1435: flag=_wrap_LinksSolidShapesVector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 1436: flag=_wrap_LinksSolidShapesVector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 1437: flag=_wrap_LinksSolidShapesVector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 1438: flag=_wrap_LinksSolidShapesVector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 1439: flag=_wrap_LinksSolidShapesVector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 1440: flag=_wrap_LinksSolidShapesVector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 1441: flag=_wrap_LinksSolidShapesVector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 1442: flag=_wrap_LinksSolidShapesVector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 1443: flag=_wrap_LinksSolidShapesVector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1444: flag=_wrap_LinksSolidShapesVector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 1445: flag=_wrap_new_LinksSolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1446: flag=_wrap_LinksSolidShapesVector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1447: flag=_wrap_LinksSolidShapesVector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 1448: flag=_wrap_LinksSolidShapesVector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1449: flag=_wrap_LinksSolidShapesVector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 1450: flag=_wrap_LinksSolidShapesVector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1451: flag=_wrap_LinksSolidShapesVector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 1452: flag=_wrap_LinksSolidShapesVector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 1453: flag=_wrap_LinksSolidShapesVector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 1454: flag=_wrap_delete_LinksSolidShapesVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1455: flag=_wrap_ForwardPositionKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1456: flag=_wrap_ForwardVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1457: flag=_wrap_ForwardPosVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1458: flag=_wrap_ForwardPosVelKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1459: flag=_wrap_ForwardAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1460: flag=_wrap_ForwardBiasAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1461: flag=_wrap_ComputeLinearAndAngularMomentum(resc,resv,argc,(mxArray**)(argv)); break; + case 1462: flag=_wrap_ComputeLinearAndAngularMomentumDerivativeBias(resc,resv,argc,(mxArray**)(argv)); break; + case 1463: flag=_wrap_RNEADynamicPhase(resc,resv,argc,(mxArray**)(argv)); break; + case 1464: flag=_wrap_CompositeRigidBodyAlgorithm(resc,resv,argc,(mxArray**)(argv)); break; + case 1465: flag=_wrap_new_ArticulatedBodyAlgorithmInternalBuffers(resc,resv,argc,(mxArray**)(argv)); break; + case 1466: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1467: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1468: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_S_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1469: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_S_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1470: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_U_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1471: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_U_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1472: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_D_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1473: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_D_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1474: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_u_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1475: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_u_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1476: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1477: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksVel_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1478: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1479: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasAcceleration_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1480: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1481: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksAccelerations_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1482: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1483: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linkABIs_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1484: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1485: flag=_wrap_ArticulatedBodyAlgorithmInternalBuffers_linksBiasWrench_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1486: flag=_wrap_delete_ArticulatedBodyAlgorithmInternalBuffers(resc,resv,argc,(mxArray**)(argv)); break; + case 1487: flag=_wrap_ArticulatedBodyAlgorithm(resc,resv,argc,(mxArray**)(argv)); break; + case 1488: flag=_wrap_InverseDynamicsInertialParametersRegressor(resc,resv,argc,(mxArray**)(argv)); break; + case 1489: flag=_wrap_DHLink_A_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1490: flag=_wrap_DHLink_A_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1491: flag=_wrap_DHLink_D_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1492: flag=_wrap_DHLink_D_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1493: flag=_wrap_DHLink_Alpha_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1494: flag=_wrap_DHLink_Alpha_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1495: flag=_wrap_DHLink_Offset_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1496: flag=_wrap_DHLink_Offset_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1497: flag=_wrap_DHLink_Min_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1498: flag=_wrap_DHLink_Min_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1499: flag=_wrap_DHLink_Max_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1500: flag=_wrap_DHLink_Max_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1501: flag=_wrap_new_DHLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1502: flag=_wrap_delete_DHLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1503: flag=_wrap_DHChain_setNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1504: flag=_wrap_DHChain_getNrOfDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1505: flag=_wrap_DHChain_setH0(resc,resv,argc,(mxArray**)(argv)); break; + case 1506: flag=_wrap_DHChain_getH0(resc,resv,argc,(mxArray**)(argv)); break; + case 1507: flag=_wrap_DHChain_setHN(resc,resv,argc,(mxArray**)(argv)); break; + case 1508: flag=_wrap_DHChain_getHN(resc,resv,argc,(mxArray**)(argv)); break; + case 1509: flag=_wrap_DHChain_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 1510: flag=_wrap_DHChain_getDOFName(resc,resv,argc,(mxArray**)(argv)); break; + case 1511: flag=_wrap_DHChain_setDOFName(resc,resv,argc,(mxArray**)(argv)); break; + case 1512: flag=_wrap_DHChain_toModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1513: flag=_wrap_DHChain_fromModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1514: flag=_wrap_new_DHChain(resc,resv,argc,(mxArray**)(argv)); break; + case 1515: flag=_wrap_delete_DHChain(resc,resv,argc,(mxArray**)(argv)); break; + case 1516: flag=_wrap_TransformFromDHCraig1989(resc,resv,argc,(mxArray**)(argv)); break; + case 1517: flag=_wrap_TransformFromDH(resc,resv,argc,(mxArray**)(argv)); break; + case 1518: flag=_wrap_ExtractDHChainFromModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1519: flag=_wrap_CreateModelFromDHChain(resc,resv,argc,(mxArray**)(argv)); break; + case 1520: flag=_wrap_dofsListFromURDF(resc,resv,argc,(mxArray**)(argv)); break; + case 1521: flag=_wrap_dofsListFromURDFString(resc,resv,argc,(mxArray**)(argv)); break; + case 1522: flag=_wrap_ModelParserOptions_addSensorFramesAsAdditionalFrames_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1523: flag=_wrap_ModelParserOptions_addSensorFramesAsAdditionalFrames_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1524: flag=_wrap_ModelParserOptions_originalFilename_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1525: flag=_wrap_ModelParserOptions_originalFilename_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1526: flag=_wrap_new_ModelParserOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1527: flag=_wrap_delete_ModelParserOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1528: flag=_wrap_new_ModelLoader(resc,resv,argc,(mxArray**)(argv)); break; + case 1529: flag=_wrap_delete_ModelLoader(resc,resv,argc,(mxArray**)(argv)); break; + case 1530: flag=_wrap_ModelLoader_parsingOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1531: flag=_wrap_ModelLoader_setParsingOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1532: flag=_wrap_ModelLoader_loadModelFromString(resc,resv,argc,(mxArray**)(argv)); break; + case 1533: flag=_wrap_ModelLoader_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1534: flag=_wrap_ModelLoader_loadReducedModelFromFullModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1535: flag=_wrap_ModelLoader_loadReducedModelFromString(resc,resv,argc,(mxArray**)(argv)); break; + case 1536: flag=_wrap_ModelLoader_loadReducedModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1537: flag=_wrap_ModelLoader_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1538: flag=_wrap_ModelLoader_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1539: flag=_wrap_ModelLoader_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1540: flag=_wrap_ModelExporterOptions_baseLink_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1541: flag=_wrap_ModelExporterOptions_baseLink_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1542: flag=_wrap_ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1543: flag=_wrap_ModelExporterOptions_exportFirstBaseLinkAdditionalFrameAsFakeURDFBase_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1544: flag=_wrap_ModelExporterOptions_robotExportedName_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1545: flag=_wrap_ModelExporterOptions_robotExportedName_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1546: flag=_wrap_ModelExporterOptions_xmlBlobs_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1547: flag=_wrap_ModelExporterOptions_xmlBlobs_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1548: flag=_wrap_new_ModelExporterOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1549: flag=_wrap_delete_ModelExporterOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1550: flag=_wrap_new_ModelExporter(resc,resv,argc,(mxArray**)(argv)); break; + case 1551: flag=_wrap_delete_ModelExporter(resc,resv,argc,(mxArray**)(argv)); break; + case 1552: flag=_wrap_ModelExporter_exportingOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1553: flag=_wrap_ModelExporter_setExportingOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1554: flag=_wrap_ModelExporter_init(resc,resv,argc,(mxArray**)(argv)); break; + case 1555: flag=_wrap_ModelExporter_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1556: flag=_wrap_ModelExporter_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1557: flag=_wrap_ModelExporter_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1558: flag=_wrap_ModelExporter_exportModelToString(resc,resv,argc,(mxArray**)(argv)); break; + case 1559: flag=_wrap_ModelExporter_exportModelToFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1560: flag=_wrap_new_ModelCalibrationHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 1561: flag=_wrap_delete_ModelCalibrationHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 1562: flag=_wrap_ModelCalibrationHelper_loadModelFromString(resc,resv,argc,(mxArray**)(argv)); break; + case 1563: flag=_wrap_ModelCalibrationHelper_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1564: flag=_wrap_ModelCalibrationHelper_updateModelInertialParametersToString(resc,resv,argc,(mxArray**)(argv)); break; + case 1565: flag=_wrap_ModelCalibrationHelper_updateModelInertialParametersToFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1566: flag=_wrap_ModelCalibrationHelper_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1567: flag=_wrap_ModelCalibrationHelper_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1568: flag=_wrap_ModelCalibrationHelper_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1569: flag=_wrap_new_UnknownWrenchContact(resc,resv,argc,(mxArray**)(argv)); break; + case 1570: flag=_wrap_UnknownWrenchContact_unknownType_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1571: flag=_wrap_UnknownWrenchContact_unknownType_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1572: flag=_wrap_UnknownWrenchContact_contactPoint_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1573: flag=_wrap_UnknownWrenchContact_contactPoint_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1574: flag=_wrap_UnknownWrenchContact_forceDirection_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1575: flag=_wrap_UnknownWrenchContact_forceDirection_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1576: flag=_wrap_UnknownWrenchContact_knownWrench_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1577: flag=_wrap_UnknownWrenchContact_knownWrench_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1578: flag=_wrap_UnknownWrenchContact_contactId_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1579: flag=_wrap_UnknownWrenchContact_contactId_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1580: flag=_wrap_delete_UnknownWrenchContact(resc,resv,argc,(mxArray**)(argv)); break; + case 1581: flag=_wrap_new_LinkUnknownWrenchContacts(resc,resv,argc,(mxArray**)(argv)); break; + case 1582: flag=_wrap_LinkUnknownWrenchContacts_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 1583: flag=_wrap_LinkUnknownWrenchContacts_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1584: flag=_wrap_LinkUnknownWrenchContacts_getNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1585: flag=_wrap_LinkUnknownWrenchContacts_setNrOfContactsForLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1586: flag=_wrap_LinkUnknownWrenchContacts_addNewContactForLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1587: flag=_wrap_LinkUnknownWrenchContacts_addNewContactInFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 1588: flag=_wrap_LinkUnknownWrenchContacts_addNewUnknownFullWrenchInFrameOrigin(resc,resv,argc,(mxArray**)(argv)); break; + case 1589: flag=_wrap_LinkUnknownWrenchContacts_contactWrench(resc,resv,argc,(mxArray**)(argv)); break; + case 1590: flag=_wrap_LinkUnknownWrenchContacts_toString(resc,resv,argc,(mxArray**)(argv)); break; + case 1591: flag=_wrap_delete_LinkUnknownWrenchContacts(resc,resv,argc,(mxArray**)(argv)); break; + case 1592: flag=_wrap_new_estimateExternalWrenchesBuffers(resc,resv,argc,(mxArray**)(argv)); break; + case 1593: flag=_wrap_estimateExternalWrenchesBuffers_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1594: flag=_wrap_estimateExternalWrenchesBuffers_getNrOfSubModels(resc,resv,argc,(mxArray**)(argv)); break; + case 1595: flag=_wrap_estimateExternalWrenchesBuffers_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1596: flag=_wrap_estimateExternalWrenchesBuffers_isConsistent(resc,resv,argc,(mxArray**)(argv)); break; + case 1597: flag=_wrap_estimateExternalWrenchesBuffers_A_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1598: flag=_wrap_estimateExternalWrenchesBuffers_A_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1599: flag=_wrap_estimateExternalWrenchesBuffers_x_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1600: flag=_wrap_estimateExternalWrenchesBuffers_x_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1601: flag=_wrap_estimateExternalWrenchesBuffers_b_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1602: flag=_wrap_estimateExternalWrenchesBuffers_b_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1603: flag=_wrap_estimateExternalWrenchesBuffers_b_contacts_subtree_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1604: flag=_wrap_estimateExternalWrenchesBuffers_b_contacts_subtree_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1605: flag=_wrap_estimateExternalWrenchesBuffers_subModelBase_H_link_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1606: flag=_wrap_estimateExternalWrenchesBuffers_subModelBase_H_link_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1607: flag=_wrap_delete_estimateExternalWrenchesBuffers(resc,resv,argc,(mxArray**)(argv)); break; + case 1608: flag=_wrap_estimateExternalWrenchesWithoutInternalFT(resc,resv,argc,(mxArray**)(argv)); break; + case 1609: flag=_wrap_estimateExternalWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 1610: flag=_wrap_dynamicsEstimationForwardVelAccKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1611: flag=_wrap_dynamicsEstimationForwardVelKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1612: flag=_wrap_computeLinkNetWrenchesWithoutGravity(resc,resv,argc,(mxArray**)(argv)); break; + case 1613: flag=_wrap_estimateLinkContactWrenchesFromLinkNetExternalWrenches(resc,resv,argc,(mxArray**)(argv)); break; + case 1614: flag=_wrap_new_ExtWrenchesAndJointTorquesEstimator(resc,resv,argc,(mxArray**)(argv)); break; + case 1615: flag=_wrap_delete_ExtWrenchesAndJointTorquesEstimator(resc,resv,argc,(mxArray**)(argv)); break; + case 1616: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_setModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1617: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_setModelAndSensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1618: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFile(resc,resv,argc,(mxArray**)(argv)); break; + case 1619: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_loadModelAndSensorsFromFileWithSpecifiedDOFs(resc,resv,argc,(mxArray**)(argv)); break; + case 1620: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1621: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1622: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_submodels(resc,resv,argc,(mxArray**)(argv)); break; + case 1623: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1624: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_updateKinematicsFromFixedBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1625: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_computeExpectedFTSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1626: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_computeSubModelMatrixRelatingFTSensorsMeasuresAndKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1627: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_estimateExtWrenchesAndJointTorques(resc,resv,argc,(mxArray**)(argv)); break; + case 1628: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_checkThatTheModelIsStill(resc,resv,argc,(mxArray**)(argv)); break; + case 1629: flag=_wrap_ExtWrenchesAndJointTorquesEstimator_estimateLinkNetWrenchesWithoutGravity(resc,resv,argc,(mxArray**)(argv)); break; + case 1630: flag=_wrap_new_SimpleLeggedOdometry(resc,resv,argc,(mxArray**)(argv)); break; + case 1631: flag=_wrap_delete_SimpleLeggedOdometry(resc,resv,argc,(mxArray**)(argv)); break; + case 1632: flag=_wrap_SimpleLeggedOdometry_setModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1633: flag=_wrap_SimpleLeggedOdometry_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1634: flag=_wrap_SimpleLeggedOdometry_updateKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 1635: flag=_wrap_SimpleLeggedOdometry_init(resc,resv,argc,(mxArray**)(argv)); break; + case 1636: flag=_wrap_SimpleLeggedOdometry_changeFixedFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 1637: flag=_wrap_SimpleLeggedOdometry_getCurrentFixedLink(resc,resv,argc,(mxArray**)(argv)); break; + case 1638: flag=_wrap_SimpleLeggedOdometry_getWorldLinkTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1639: flag=_wrap_SimpleLeggedOdometry_getWorldFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1640: flag=_wrap_isLinkBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1641: flag=_wrap_isJointBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1642: flag=_wrap_isDOFBerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1643: flag=_wrap_new_BerdyOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1644: flag=_wrap_BerdyOptions_berdyVariant_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1645: flag=_wrap_BerdyOptions_berdyVariant_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1646: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1647: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsDynamicVariables_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1648: flag=_wrap_BerdyOptions_includeAllJointAccelerationsAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1649: flag=_wrap_BerdyOptions_includeAllJointAccelerationsAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1650: flag=_wrap_BerdyOptions_includeAllJointTorquesAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1651: flag=_wrap_BerdyOptions_includeAllJointTorquesAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1652: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsSensors_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1653: flag=_wrap_BerdyOptions_includeAllNetExternalWrenchesAsSensors_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1654: flag=_wrap_BerdyOptions_includeFixedBaseExternalWrench_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1655: flag=_wrap_BerdyOptions_includeFixedBaseExternalWrench_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1656: flag=_wrap_BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1657: flag=_wrap_BerdyOptions_jointOnWhichTheInternalWrenchIsMeasured_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1658: flag=_wrap_BerdyOptions_baseLink_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1659: flag=_wrap_BerdyOptions_baseLink_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1660: flag=_wrap_BerdyOptions_checkConsistency(resc,resv,argc,(mxArray**)(argv)); break; + case 1661: flag=_wrap_delete_BerdyOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1662: flag=_wrap_BerdySensor_type_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1663: flag=_wrap_BerdySensor_type_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1664: flag=_wrap_BerdySensor_id_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1665: flag=_wrap_BerdySensor_id_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1666: flag=_wrap_BerdySensor_range_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1667: flag=_wrap_BerdySensor_range_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1668: flag=_wrap_BerdySensor_eq(resc,resv,argc,(mxArray**)(argv)); break; + case 1669: flag=_wrap_BerdySensor_lt(resc,resv,argc,(mxArray**)(argv)); break; + case 1670: flag=_wrap_new_BerdySensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1671: flag=_wrap_delete_BerdySensor(resc,resv,argc,(mxArray**)(argv)); break; + case 1672: flag=_wrap_BerdyDynamicVariable_type_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1673: flag=_wrap_BerdyDynamicVariable_type_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1674: flag=_wrap_BerdyDynamicVariable_id_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1675: flag=_wrap_BerdyDynamicVariable_id_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1676: flag=_wrap_BerdyDynamicVariable_range_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1677: flag=_wrap_BerdyDynamicVariable_range_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1678: flag=_wrap_BerdyDynamicVariable_eq(resc,resv,argc,(mxArray**)(argv)); break; + case 1679: flag=_wrap_BerdyDynamicVariable_lt(resc,resv,argc,(mxArray**)(argv)); break; + case 1680: flag=_wrap_new_BerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1681: flag=_wrap_delete_BerdyDynamicVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1682: flag=_wrap_new_BerdyHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 1683: flag=_wrap_BerdyHelper_dynamicTraversal(resc,resv,argc,(mxArray**)(argv)); break; + case 1684: flag=_wrap_BerdyHelper_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1685: flag=_wrap_BerdyHelper_sensors(resc,resv,argc,(mxArray**)(argv)); break; + case 1686: flag=_wrap_BerdyHelper_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1687: flag=_wrap_BerdyHelper_init(resc,resv,argc,(mxArray**)(argv)); break; + case 1688: flag=_wrap_BerdyHelper_getOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 1689: flag=_wrap_BerdyHelper_getNrOfDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 1690: flag=_wrap_BerdyHelper_getNrOfDynamicEquations(resc,resv,argc,(mxArray**)(argv)); break; + case 1691: flag=_wrap_BerdyHelper_getNrOfSensorsMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1692: flag=_wrap_BerdyHelper_resizeAndZeroBerdyMatrices(resc,resv,argc,(mxArray**)(argv)); break; + case 1693: flag=_wrap_BerdyHelper_getBerdyMatrices(resc,resv,argc,(mxArray**)(argv)); break; + case 1694: flag=_wrap_BerdyHelper_getSensorsOrdering(resc,resv,argc,(mxArray**)(argv)); break; + case 1695: flag=_wrap_BerdyHelper_getRangeSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1696: flag=_wrap_BerdyHelper_getRangeDOFSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1697: flag=_wrap_BerdyHelper_getRangeJointSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1698: flag=_wrap_BerdyHelper_getRangeLinkSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1699: flag=_wrap_BerdyHelper_getRangeRCMSensorVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1700: flag=_wrap_BerdyHelper_getRangeLinkVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1701: flag=_wrap_BerdyHelper_getRangeJointVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1702: flag=_wrap_BerdyHelper_getRangeDOFVariable(resc,resv,argc,(mxArray**)(argv)); break; + case 1703: flag=_wrap_BerdyHelper_getDynamicVariablesOrdering(resc,resv,argc,(mxArray**)(argv)); break; + case 1704: flag=_wrap_BerdyHelper_serializeDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 1705: flag=_wrap_BerdyHelper_serializeSensorVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 1706: flag=_wrap_BerdyHelper_serializeDynamicVariablesComputedFromFixedBaseRNEA(resc,resv,argc,(mxArray**)(argv)); break; + case 1707: flag=_wrap_BerdyHelper_extractJointTorquesFromDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 1708: flag=_wrap_BerdyHelper_extractLinkNetExternalWrenchesFromDynamicVariables(resc,resv,argc,(mxArray**)(argv)); break; + case 1709: flag=_wrap_BerdyHelper_updateKinematicsFromFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1710: flag=_wrap_BerdyHelper_updateKinematicsFromFixedBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1711: flag=_wrap_BerdyHelper_updateKinematicsFromTraversalFixedBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1712: flag=_wrap_BerdyHelper_setNetExternalWrenchMeasurementFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 1713: flag=_wrap_BerdyHelper_getNetExternalWrenchMeasurementFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 1714: flag=_wrap_delete_BerdyHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 1715: flag=_wrap_new_BerdySparseMAPSolver(resc,resv,argc,(mxArray**)(argv)); break; + case 1716: flag=_wrap_delete_BerdySparseMAPSolver(resc,resv,argc,(mxArray**)(argv)); break; + case 1717: flag=_wrap_BerdySparseMAPSolver_setDynamicsConstraintsPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1718: flag=_wrap_BerdySparseMAPSolver_setDynamicsRegularizationPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1719: flag=_wrap_BerdySparseMAPSolver_setDynamicsRegularizationPriorExpectedValue(resc,resv,argc,(mxArray**)(argv)); break; + case 1720: flag=_wrap_BerdySparseMAPSolver_setMeasurementsPriorCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1721: flag=_wrap_BerdySparseMAPSolver_dynamicsConstraintsPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 1722: flag=_wrap_BerdySparseMAPSolver_dynamicsRegularizationPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 1723: flag=_wrap_BerdySparseMAPSolver_dynamicsRegularizationPriorExpectedValue(resc,resv,argc,(mxArray**)(argv)); break; + case 1724: flag=_wrap_BerdySparseMAPSolver_measurementsPriorCovarianceInverse(resc,resv,argc,(mxArray**)(argv)); break; + case 1725: flag=_wrap_BerdySparseMAPSolver_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1726: flag=_wrap_BerdySparseMAPSolver_initialize(resc,resv,argc,(mxArray**)(argv)); break; + case 1727: flag=_wrap_BerdySparseMAPSolver_updateEstimateInformationFixedBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1728: flag=_wrap_BerdySparseMAPSolver_updateEstimateInformationFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1729: flag=_wrap_BerdySparseMAPSolver_doEstimate(resc,resv,argc,(mxArray**)(argv)); break; + case 1730: flag=_wrap_BerdySparseMAPSolver_getLastEstimate(resc,resv,argc,(mxArray**)(argv)); break; + case 1731: flag=_wrap_AttitudeEstimatorState_m_orientation_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1732: flag=_wrap_AttitudeEstimatorState_m_orientation_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1733: flag=_wrap_AttitudeEstimatorState_m_angular_velocity_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1734: flag=_wrap_AttitudeEstimatorState_m_angular_velocity_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1735: flag=_wrap_AttitudeEstimatorState_m_gyroscope_bias_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1736: flag=_wrap_AttitudeEstimatorState_m_gyroscope_bias_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1737: flag=_wrap_new_AttitudeEstimatorState(resc,resv,argc,(mxArray**)(argv)); break; + case 1738: flag=_wrap_delete_AttitudeEstimatorState(resc,resv,argc,(mxArray**)(argv)); break; + case 1739: flag=_wrap_delete_IAttitudeEstimator(resc,resv,argc,(mxArray**)(argv)); break; + case 1740: flag=_wrap_IAttitudeEstimator_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1741: flag=_wrap_IAttitudeEstimator_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; + case 1742: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1743: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 1744: flag=_wrap_IAttitudeEstimator_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; + case 1745: flag=_wrap_IAttitudeEstimator_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1746: flag=_wrap_IAttitudeEstimator_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1747: flag=_wrap_IAttitudeEstimator_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; + case 1748: flag=_wrap_IAttitudeEstimator_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1749: flag=_wrap_IAttitudeEstimator_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; + case 1750: flag=_wrap_AttitudeMahonyFilterParameters_time_step_in_seconds_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1751: flag=_wrap_AttitudeMahonyFilterParameters_time_step_in_seconds_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1752: flag=_wrap_AttitudeMahonyFilterParameters_kp_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1753: flag=_wrap_AttitudeMahonyFilterParameters_kp_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1754: flag=_wrap_AttitudeMahonyFilterParameters_ki_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1755: flag=_wrap_AttitudeMahonyFilterParameters_ki_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1756: flag=_wrap_AttitudeMahonyFilterParameters_use_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1757: flag=_wrap_AttitudeMahonyFilterParameters_use_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1758: flag=_wrap_AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1759: flag=_wrap_AttitudeMahonyFilterParameters_confidence_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1760: flag=_wrap_new_AttitudeMahonyFilterParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1761: flag=_wrap_delete_AttitudeMahonyFilterParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1762: flag=_wrap_new_AttitudeMahonyFilter(resc,resv,argc,(mxArray**)(argv)); break; + case 1763: flag=_wrap_AttitudeMahonyFilter_useMagnetoMeterMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1764: flag=_wrap_AttitudeMahonyFilter_setConfidenceForMagnetometerMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1765: flag=_wrap_AttitudeMahonyFilter_setGainkp(resc,resv,argc,(mxArray**)(argv)); break; + case 1766: flag=_wrap_AttitudeMahonyFilter_setGainki(resc,resv,argc,(mxArray**)(argv)); break; + case 1767: flag=_wrap_AttitudeMahonyFilter_setTimeStepInSeconds(resc,resv,argc,(mxArray**)(argv)); break; + case 1768: flag=_wrap_AttitudeMahonyFilter_setGravityDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1769: flag=_wrap_AttitudeMahonyFilter_setParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1770: flag=_wrap_AttitudeMahonyFilter_getParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1771: flag=_wrap_AttitudeMahonyFilter_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1772: flag=_wrap_AttitudeMahonyFilter_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; + case 1773: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1774: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 1775: flag=_wrap_AttitudeMahonyFilter_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; + case 1776: flag=_wrap_AttitudeMahonyFilter_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1777: flag=_wrap_AttitudeMahonyFilter_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1778: flag=_wrap_AttitudeMahonyFilter_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; + case 1779: flag=_wrap_AttitudeMahonyFilter_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1780: flag=_wrap_AttitudeMahonyFilter_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; + case 1781: flag=_wrap_delete_AttitudeMahonyFilter(resc,resv,argc,(mxArray**)(argv)); break; + case 1782: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekf_f(resc,resv,argc,(mxArray**)(argv)); break; + case 1783: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekf_h(resc,resv,argc,(mxArray**)(argv)); break; + case 1784: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianF(resc,resv,argc,(mxArray**)(argv)); break; + case 1785: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfComputeJacobianH(resc,resv,argc,(mxArray**)(argv)); break; + case 1786: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfPredict(resc,resv,argc,(mxArray**)(argv)); break; + case 1787: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfUpdate(resc,resv,argc,(mxArray**)(argv)); break; + case 1788: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfInit(resc,resv,argc,(mxArray**)(argv)); break; + case 1789: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfReset(resc,resv,argc,(mxArray**)(argv)); break; + case 1790: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1791: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInputVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1792: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInitialState(resc,resv,argc,(mxArray**)(argv)); break; + case 1793: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1794: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetSystemNoiseCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1795: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetMeasurementNoiseCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1796: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetStateSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1797: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetInputSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1798: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfSetOutputSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1799: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfGetStates(resc,resv,argc,(mxArray**)(argv)); break; + case 1800: flag=_wrap_DiscreteExtendedKalmanFilterHelper_ekfGetStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1801: flag=_wrap_delete_DiscreteExtendedKalmanFilterHelper(resc,resv,argc,(mxArray**)(argv)); break; + case 1802: flag=_wrap_output_dimensions_with_magnetometer_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1803: flag=_wrap_output_dimensions_without_magnetometer_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1804: flag=_wrap_input_dimensions_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1805: flag=_wrap_AttitudeQuaternionEKFParameters_time_step_in_seconds_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1806: flag=_wrap_AttitudeQuaternionEKFParameters_time_step_in_seconds_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1807: flag=_wrap_AttitudeQuaternionEKFParameters_bias_correlation_time_factor_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1808: flag=_wrap_AttitudeQuaternionEKFParameters_bias_correlation_time_factor_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1809: flag=_wrap_AttitudeQuaternionEKFParameters_accelerometer_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1810: flag=_wrap_AttitudeQuaternionEKFParameters_accelerometer_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1811: flag=_wrap_AttitudeQuaternionEKFParameters_magnetometer_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1812: flag=_wrap_AttitudeQuaternionEKFParameters_magnetometer_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1813: flag=_wrap_AttitudeQuaternionEKFParameters_gyroscope_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1814: flag=_wrap_AttitudeQuaternionEKFParameters_gyroscope_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1815: flag=_wrap_AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1816: flag=_wrap_AttitudeQuaternionEKFParameters_gyro_bias_noise_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1817: flag=_wrap_AttitudeQuaternionEKFParameters_initial_orientation_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1818: flag=_wrap_AttitudeQuaternionEKFParameters_initial_orientation_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1819: flag=_wrap_AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1820: flag=_wrap_AttitudeQuaternionEKFParameters_initial_ang_vel_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1821: flag=_wrap_AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1822: flag=_wrap_AttitudeQuaternionEKFParameters_initial_gyro_bias_error_variance_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1823: flag=_wrap_AttitudeQuaternionEKFParameters_use_magnetometer_measurements_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1824: flag=_wrap_AttitudeQuaternionEKFParameters_use_magnetometer_measurements_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1825: flag=_wrap_new_AttitudeQuaternionEKFParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1826: flag=_wrap_delete_AttitudeQuaternionEKFParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1827: flag=_wrap_new_AttitudeQuaternionEKF(resc,resv,argc,(mxArray**)(argv)); break; + case 1828: flag=_wrap_AttitudeQuaternionEKF_getParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1829: flag=_wrap_AttitudeQuaternionEKF_setParameters(resc,resv,argc,(mxArray**)(argv)); break; + case 1830: flag=_wrap_AttitudeQuaternionEKF_setGravityDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1831: flag=_wrap_AttitudeQuaternionEKF_setTimeStepInSeconds(resc,resv,argc,(mxArray**)(argv)); break; + case 1832: flag=_wrap_AttitudeQuaternionEKF_setBiasCorrelationTimeFactor(resc,resv,argc,(mxArray**)(argv)); break; + case 1833: flag=_wrap_AttitudeQuaternionEKF_useMagnetometerMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1834: flag=_wrap_AttitudeQuaternionEKF_setMeasurementNoiseVariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1835: flag=_wrap_AttitudeQuaternionEKF_setSystemNoiseVariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1836: flag=_wrap_AttitudeQuaternionEKF_setInitialStateCovariance(resc,resv,argc,(mxArray**)(argv)); break; + case 1837: flag=_wrap_AttitudeQuaternionEKF_initializeFilter(resc,resv,argc,(mxArray**)(argv)); break; + case 1838: flag=_wrap_AttitudeQuaternionEKF_updateFilterWithMeasurements(resc,resv,argc,(mxArray**)(argv)); break; + case 1839: flag=_wrap_AttitudeQuaternionEKF_propagateStates(resc,resv,argc,(mxArray**)(argv)); break; + case 1840: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsRotationMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1841: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsQuaternion(resc,resv,argc,(mxArray**)(argv)); break; + case 1842: flag=_wrap_AttitudeQuaternionEKF_getOrientationEstimateAsRPY(resc,resv,argc,(mxArray**)(argv)); break; + case 1843: flag=_wrap_AttitudeQuaternionEKF_getInternalStateSize(resc,resv,argc,(mxArray**)(argv)); break; + case 1844: flag=_wrap_AttitudeQuaternionEKF_getInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1845: flag=_wrap_AttitudeQuaternionEKF_getDefaultInternalInitialState(resc,resv,argc,(mxArray**)(argv)); break; + case 1846: flag=_wrap_AttitudeQuaternionEKF_setInternalState(resc,resv,argc,(mxArray**)(argv)); break; + case 1847: flag=_wrap_AttitudeQuaternionEKF_setInternalStateInitialOrientation(resc,resv,argc,(mxArray**)(argv)); break; + case 1848: flag=_wrap_delete_AttitudeQuaternionEKF(resc,resv,argc,(mxArray**)(argv)); break; + case 1849: flag=_wrap_estimateInertialParametersFromLinkBoundingBoxesAndTotalMass(resc,resv,argc,(mxArray**)(argv)); break; + case 1850: flag=_wrap_computeBoundingBoxFromShape(resc,resv,argc,(mxArray**)(argv)); break; + case 1851: flag=_wrap_computeBoxVertices(resc,resv,argc,(mxArray**)(argv)); break; + case 1852: flag=_wrap_new_KinDynComputations(resc,resv,argc,(mxArray**)(argv)); break; + case 1853: flag=_wrap_delete_KinDynComputations(resc,resv,argc,(mxArray**)(argv)); break; + case 1854: flag=_wrap_KinDynComputations_loadRobotModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1855: flag=_wrap_KinDynComputations_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 1856: flag=_wrap_KinDynComputations_setFrameVelocityRepresentation(resc,resv,argc,(mxArray**)(argv)); break; + case 1857: flag=_wrap_KinDynComputations_getFrameVelocityRepresentation(resc,resv,argc,(mxArray**)(argv)); break; + case 1858: flag=_wrap_KinDynComputations_getNrOfDegreesOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; + case 1859: flag=_wrap_KinDynComputations_getDescriptionOfDegreeOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; + case 1860: flag=_wrap_KinDynComputations_getDescriptionOfDegreesOfFreedom(resc,resv,argc,(mxArray**)(argv)); break; + case 1861: flag=_wrap_KinDynComputations_getNrOfLinks(resc,resv,argc,(mxArray**)(argv)); break; + case 1862: flag=_wrap_KinDynComputations_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; + case 1863: flag=_wrap_KinDynComputations_getFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1864: flag=_wrap_KinDynComputations_setFloatingBase(resc,resv,argc,(mxArray**)(argv)); break; + case 1865: flag=_wrap_KinDynComputations_model(resc,resv,argc,(mxArray**)(argv)); break; + case 1866: flag=_wrap_KinDynComputations_getRobotModel(resc,resv,argc,(mxArray**)(argv)); break; + case 1867: flag=_wrap_KinDynComputations_getRelativeJacobianSparsityPattern(resc,resv,argc,(mxArray**)(argv)); break; + case 1868: flag=_wrap_KinDynComputations_getFrameFreeFloatingJacobianSparsityPattern(resc,resv,argc,(mxArray**)(argv)); break; + case 1869: flag=_wrap_KinDynComputations_setJointPos(resc,resv,argc,(mxArray**)(argv)); break; + case 1870: flag=_wrap_KinDynComputations_setRobotState(resc,resv,argc,(mxArray**)(argv)); break; + case 1871: flag=_wrap_KinDynComputations_getRobotState(resc,resv,argc,(mxArray**)(argv)); break; + case 1872: flag=_wrap_KinDynComputations_getWorldBaseTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1873: flag=_wrap_KinDynComputations_getBaseTwist(resc,resv,argc,(mxArray**)(argv)); break; + case 1874: flag=_wrap_KinDynComputations_getJointPos(resc,resv,argc,(mxArray**)(argv)); break; + case 1875: flag=_wrap_KinDynComputations_getJointVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1876: flag=_wrap_KinDynComputations_getModelVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1877: flag=_wrap_KinDynComputations_getFrameIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 1878: flag=_wrap_KinDynComputations_getFrameName(resc,resv,argc,(mxArray**)(argv)); break; + case 1879: flag=_wrap_KinDynComputations_getWorldTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1880: flag=_wrap_KinDynComputations_getWorldTransformsAsHomogeneous(resc,resv,argc,(mxArray**)(argv)); break; + case 1881: flag=_wrap_KinDynComputations_getRelativeTransformExplicit(resc,resv,argc,(mxArray**)(argv)); break; + case 1882: flag=_wrap_KinDynComputations_getRelativeTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 1883: flag=_wrap_KinDynComputations_getFrameVel(resc,resv,argc,(mxArray**)(argv)); break; + case 1884: flag=_wrap_KinDynComputations_getFrameAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1885: flag=_wrap_KinDynComputations_getFrameFreeFloatingJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1886: flag=_wrap_KinDynComputations_getRelativeJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1887: flag=_wrap_KinDynComputations_getRelativeJacobianExplicit(resc,resv,argc,(mxArray**)(argv)); break; + case 1888: flag=_wrap_KinDynComputations_getFrameBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1889: flag=_wrap_KinDynComputations_getCenterOfMassPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 1890: flag=_wrap_KinDynComputations_getCenterOfMassVelocity(resc,resv,argc,(mxArray**)(argv)); break; + case 1891: flag=_wrap_KinDynComputations_getCenterOfMassJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1892: flag=_wrap_KinDynComputations_getCenterOfMassBiasAcc(resc,resv,argc,(mxArray**)(argv)); break; + case 1893: flag=_wrap_KinDynComputations_getAverageVelocity(resc,resv,argc,(mxArray**)(argv)); break; + case 1894: flag=_wrap_KinDynComputations_getAverageVelocityJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1895: flag=_wrap_KinDynComputations_getCentroidalAverageVelocity(resc,resv,argc,(mxArray**)(argv)); break; + case 1896: flag=_wrap_KinDynComputations_getCentroidalAverageVelocityJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1897: flag=_wrap_KinDynComputations_getLinearAngularMomentum(resc,resv,argc,(mxArray**)(argv)); break; + case 1898: flag=_wrap_KinDynComputations_getLinearAngularMomentumJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1899: flag=_wrap_KinDynComputations_getCentroidalTotalMomentum(resc,resv,argc,(mxArray**)(argv)); break; + case 1900: flag=_wrap_KinDynComputations_getCentroidalTotalMomentumJacobian(resc,resv,argc,(mxArray**)(argv)); break; + case 1901: flag=_wrap_KinDynComputations_getFreeFloatingMassMatrix(resc,resv,argc,(mxArray**)(argv)); break; + case 1902: flag=_wrap_KinDynComputations_inverseDynamics(resc,resv,argc,(mxArray**)(argv)); break; + case 1903: flag=_wrap_KinDynComputations_inverseDynamicsWithInternalJointForceTorques(resc,resv,argc,(mxArray**)(argv)); break; + case 1904: flag=_wrap_KinDynComputations_generalizedBiasForces(resc,resv,argc,(mxArray**)(argv)); break; + case 1905: flag=_wrap_KinDynComputations_generalizedGravityForces(resc,resv,argc,(mxArray**)(argv)); break; + case 1906: flag=_wrap_KinDynComputations_generalizedExternalForces(resc,resv,argc,(mxArray**)(argv)); break; + case 1907: flag=_wrap_KinDynComputations_inverseDynamicsInertialParametersRegressor(resc,resv,argc,(mxArray**)(argv)); break; + case 1908: flag=_wrap_Matrix4x4Vector_pop(resc,resv,argc,(mxArray**)(argv)); break; + case 1909: flag=_wrap_Matrix4x4Vector_brace(resc,resv,argc,(mxArray**)(argv)); break; + case 1910: flag=_wrap_Matrix4x4Vector_setbrace(resc,resv,argc,(mxArray**)(argv)); break; + case 1911: flag=_wrap_Matrix4x4Vector_append(resc,resv,argc,(mxArray**)(argv)); break; + case 1912: flag=_wrap_Matrix4x4Vector_empty(resc,resv,argc,(mxArray**)(argv)); break; + case 1913: flag=_wrap_Matrix4x4Vector_size(resc,resv,argc,(mxArray**)(argv)); break; + case 1914: flag=_wrap_Matrix4x4Vector_swap(resc,resv,argc,(mxArray**)(argv)); break; + case 1915: flag=_wrap_Matrix4x4Vector_begin(resc,resv,argc,(mxArray**)(argv)); break; + case 1916: flag=_wrap_Matrix4x4Vector_end(resc,resv,argc,(mxArray**)(argv)); break; + case 1917: flag=_wrap_Matrix4x4Vector_rbegin(resc,resv,argc,(mxArray**)(argv)); break; + case 1918: flag=_wrap_Matrix4x4Vector_rend(resc,resv,argc,(mxArray**)(argv)); break; + case 1919: flag=_wrap_Matrix4x4Vector_clear(resc,resv,argc,(mxArray**)(argv)); break; + case 1920: flag=_wrap_Matrix4x4Vector_get_allocator(resc,resv,argc,(mxArray**)(argv)); break; + case 1921: flag=_wrap_Matrix4x4Vector_pop_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1922: flag=_wrap_Matrix4x4Vector_erase(resc,resv,argc,(mxArray**)(argv)); break; + case 1923: flag=_wrap_new_Matrix4x4Vector(resc,resv,argc,(mxArray**)(argv)); break; + case 1924: flag=_wrap_Matrix4x4Vector_push_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1925: flag=_wrap_Matrix4x4Vector_front(resc,resv,argc,(mxArray**)(argv)); break; + case 1926: flag=_wrap_Matrix4x4Vector_back(resc,resv,argc,(mxArray**)(argv)); break; + case 1927: flag=_wrap_Matrix4x4Vector_assign(resc,resv,argc,(mxArray**)(argv)); break; + case 1928: flag=_wrap_Matrix4x4Vector_resize(resc,resv,argc,(mxArray**)(argv)); break; + case 1929: flag=_wrap_Matrix4x4Vector_insert(resc,resv,argc,(mxArray**)(argv)); break; + case 1930: flag=_wrap_Matrix4x4Vector_reserve(resc,resv,argc,(mxArray**)(argv)); break; + case 1931: flag=_wrap_Matrix4x4Vector_capacity(resc,resv,argc,(mxArray**)(argv)); break; + case 1932: flag=_wrap_Matrix4x4Vector_toMatlab(resc,resv,argc,(mxArray**)(argv)); break; + case 1933: flag=_wrap_delete_Matrix4x4Vector(resc,resv,argc,(mxArray**)(argv)); break; + case 1934: flag=_wrap_ICameraAnimator_enableMouseControl(resc,resv,argc,(mxArray**)(argv)); break; + case 1935: flag=_wrap_ICameraAnimator_getMoveSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1936: flag=_wrap_ICameraAnimator_setMoveSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1937: flag=_wrap_ICameraAnimator_getRotateSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1938: flag=_wrap_ICameraAnimator_setRotateSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1939: flag=_wrap_ICameraAnimator_getZoomSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1940: flag=_wrap_ICameraAnimator_setZoomSpeed(resc,resv,argc,(mxArray**)(argv)); break; + case 1941: flag=_wrap_delete_ICameraAnimator(resc,resv,argc,(mxArray**)(argv)); break; + case 1942: flag=_wrap_delete_ICamera(resc,resv,argc,(mxArray**)(argv)); break; + case 1943: flag=_wrap_ICamera_setPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 1944: flag=_wrap_ICamera_setTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 1945: flag=_wrap_ICamera_getPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 1946: flag=_wrap_ICamera_getTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 1947: flag=_wrap_ICamera_setUpVector(resc,resv,argc,(mxArray**)(argv)); break; + case 1948: flag=_wrap_ICamera_animator(resc,resv,argc,(mxArray**)(argv)); break; + case 1949: flag=_wrap_ColorViz_r_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1950: flag=_wrap_ColorViz_r_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1951: flag=_wrap_ColorViz_g_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1952: flag=_wrap_ColorViz_g_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1953: flag=_wrap_ColorViz_b_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1954: flag=_wrap_ColorViz_b_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1955: flag=_wrap_ColorViz_a_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1956: flag=_wrap_ColorViz_a_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1957: flag=_wrap_new_ColorViz(resc,resv,argc,(mxArray**)(argv)); break; + case 1958: flag=_wrap_delete_ColorViz(resc,resv,argc,(mxArray**)(argv)); break; + case 1959: flag=_wrap_PixelViz_width_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1960: flag=_wrap_PixelViz_width_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1961: flag=_wrap_PixelViz_height_get(resc,resv,argc,(mxArray**)(argv)); break; + case 1962: flag=_wrap_PixelViz_height_set(resc,resv,argc,(mxArray**)(argv)); break; + case 1963: flag=_wrap_new_PixelViz(resc,resv,argc,(mxArray**)(argv)); break; + case 1964: flag=_wrap_delete_PixelViz(resc,resv,argc,(mxArray**)(argv)); break; + case 1965: flag=_wrap_delete_ILight(resc,resv,argc,(mxArray**)(argv)); break; + case 1966: flag=_wrap_ILight_getName(resc,resv,argc,(mxArray**)(argv)); break; + case 1967: flag=_wrap_ILight_setType(resc,resv,argc,(mxArray**)(argv)); break; + case 1968: flag=_wrap_ILight_getType(resc,resv,argc,(mxArray**)(argv)); break; + case 1969: flag=_wrap_ILight_setPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 1970: flag=_wrap_ILight_getPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 1971: flag=_wrap_ILight_setDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1972: flag=_wrap_ILight_getDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1973: flag=_wrap_ILight_setAmbientColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1974: flag=_wrap_ILight_getAmbientColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1975: flag=_wrap_ILight_setSpecularColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1976: flag=_wrap_ILight_getSpecularColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1977: flag=_wrap_ILight_setDiffuseColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1978: flag=_wrap_ILight_getDiffuseColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1979: flag=_wrap_delete_IEnvironment(resc,resv,argc,(mxArray**)(argv)); break; + case 1980: flag=_wrap_IEnvironment_getElements(resc,resv,argc,(mxArray**)(argv)); break; + case 1981: flag=_wrap_IEnvironment_setElementVisibility(resc,resv,argc,(mxArray**)(argv)); break; + case 1982: flag=_wrap_IEnvironment_setBackgroundColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1983: flag=_wrap_IEnvironment_setFloorGridColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1984: flag=_wrap_IEnvironment_setAmbientLight(resc,resv,argc,(mxArray**)(argv)); break; + case 1985: flag=_wrap_IEnvironment_getLights(resc,resv,argc,(mxArray**)(argv)); break; + case 1986: flag=_wrap_IEnvironment_addLight(resc,resv,argc,(mxArray**)(argv)); break; + case 1987: flag=_wrap_IEnvironment_lightViz(resc,resv,argc,(mxArray**)(argv)); break; + case 1988: flag=_wrap_IEnvironment_removeLight(resc,resv,argc,(mxArray**)(argv)); break; + case 1989: flag=_wrap_delete_IJetsVisualization(resc,resv,argc,(mxArray**)(argv)); break; + case 1990: flag=_wrap_IJetsVisualization_setJetsFrames(resc,resv,argc,(mxArray**)(argv)); break; + case 1991: flag=_wrap_IJetsVisualization_getNrOfJets(resc,resv,argc,(mxArray**)(argv)); break; + case 1992: flag=_wrap_IJetsVisualization_getJetDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1993: flag=_wrap_IJetsVisualization_setJetDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 1994: flag=_wrap_IJetsVisualization_setJetColor(resc,resv,argc,(mxArray**)(argv)); break; + case 1995: flag=_wrap_IJetsVisualization_setJetsDimensions(resc,resv,argc,(mxArray**)(argv)); break; + case 1996: flag=_wrap_IJetsVisualization_setJetsIntensity(resc,resv,argc,(mxArray**)(argv)); break; + case 1997: flag=_wrap_delete_ILabel(resc,resv,argc,(mxArray**)(argv)); break; + case 1998: flag=_wrap_ILabel_setText(resc,resv,argc,(mxArray**)(argv)); break; + case 1999: flag=_wrap_ILabel_getText(resc,resv,argc,(mxArray**)(argv)); break; + case 2000: flag=_wrap_ILabel_setSize(resc,resv,argc,(mxArray**)(argv)); break; + case 2001: flag=_wrap_ILabel_width(resc,resv,argc,(mxArray**)(argv)); break; + case 2002: flag=_wrap_ILabel_height(resc,resv,argc,(mxArray**)(argv)); break; + case 2003: flag=_wrap_ILabel_setPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 2004: flag=_wrap_ILabel_getPosition(resc,resv,argc,(mxArray**)(argv)); break; + case 2005: flag=_wrap_ILabel_setColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2006: flag=_wrap_ILabel_setVisible(resc,resv,argc,(mxArray**)(argv)); break; + case 2007: flag=_wrap_delete_IVectorsVisualization(resc,resv,argc,(mxArray**)(argv)); break; + case 2008: flag=_wrap_IVectorsVisualization_addVector(resc,resv,argc,(mxArray**)(argv)); break; + case 2009: flag=_wrap_IVectorsVisualization_getNrOfVectors(resc,resv,argc,(mxArray**)(argv)); break; + case 2010: flag=_wrap_IVectorsVisualization_getVector(resc,resv,argc,(mxArray**)(argv)); break; + case 2011: flag=_wrap_IVectorsVisualization_updateVector(resc,resv,argc,(mxArray**)(argv)); break; + case 2012: flag=_wrap_IVectorsVisualization_setVectorColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2013: flag=_wrap_IVectorsVisualization_setVectorsDefaultColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2014: flag=_wrap_IVectorsVisualization_setVectorsColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2015: flag=_wrap_IVectorsVisualization_setVectorsAspect(resc,resv,argc,(mxArray**)(argv)); break; + case 2016: flag=_wrap_IVectorsVisualization_setVisible(resc,resv,argc,(mxArray**)(argv)); break; + case 2017: flag=_wrap_IVectorsVisualization_getVectorLabel(resc,resv,argc,(mxArray**)(argv)); break; + case 2018: flag=_wrap_delete_IFrameVisualization(resc,resv,argc,(mxArray**)(argv)); break; + case 2019: flag=_wrap_IFrameVisualization_addFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 2020: flag=_wrap_IFrameVisualization_setVisible(resc,resv,argc,(mxArray**)(argv)); break; + case 2021: flag=_wrap_IFrameVisualization_getNrOfFrames(resc,resv,argc,(mxArray**)(argv)); break; + case 2022: flag=_wrap_IFrameVisualization_getFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 2023: flag=_wrap_IFrameVisualization_updateFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 2024: flag=_wrap_IFrameVisualization_getFrameLabel(resc,resv,argc,(mxArray**)(argv)); break; + case 2025: flag=_wrap_delete_IModelVisualization(resc,resv,argc,(mxArray**)(argv)); break; + case 2026: flag=_wrap_IModelVisualization_setPositions(resc,resv,argc,(mxArray**)(argv)); break; + case 2027: flag=_wrap_IModelVisualization_setLinkPositions(resc,resv,argc,(mxArray**)(argv)); break; + case 2028: flag=_wrap_IModelVisualization_model(resc,resv,argc,(mxArray**)(argv)); break; + case 2029: flag=_wrap_IModelVisualization_getInstanceName(resc,resv,argc,(mxArray**)(argv)); break; + case 2030: flag=_wrap_IModelVisualization_setModelVisibility(resc,resv,argc,(mxArray**)(argv)); break; + case 2031: flag=_wrap_IModelVisualization_setModelColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2032: flag=_wrap_IModelVisualization_resetModelColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2033: flag=_wrap_IModelVisualization_setLinkColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2034: flag=_wrap_IModelVisualization_resetLinkColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2035: flag=_wrap_IModelVisualization_getLinkNames(resc,resv,argc,(mxArray**)(argv)); break; + case 2036: flag=_wrap_IModelVisualization_setLinkVisibility(resc,resv,argc,(mxArray**)(argv)); break; + case 2037: flag=_wrap_IModelVisualization_getFeatures(resc,resv,argc,(mxArray**)(argv)); break; + case 2038: flag=_wrap_IModelVisualization_setFeatureVisibility(resc,resv,argc,(mxArray**)(argv)); break; + case 2039: flag=_wrap_IModelVisualization_jets(resc,resv,argc,(mxArray**)(argv)); break; + case 2040: flag=_wrap_IModelVisualization_getWorldLinkTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 2041: flag=_wrap_IModelVisualization_getWorldFrameTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 2042: flag=_wrap_IModelVisualization_label(resc,resv,argc,(mxArray**)(argv)); break; + case 2043: flag=_wrap_delete_ITexture(resc,resv,argc,(mxArray**)(argv)); break; + case 2044: flag=_wrap_ITexture_environment(resc,resv,argc,(mxArray**)(argv)); break; + case 2045: flag=_wrap_ITexture_getPixelColor(resc,resv,argc,(mxArray**)(argv)); break; + case 2046: flag=_wrap_ITexture_getPixels(resc,resv,argc,(mxArray**)(argv)); break; + case 2047: flag=_wrap_ITexture_drawToFile(resc,resv,argc,(mxArray**)(argv)); break; + case 2048: flag=_wrap_ITexture_enableDraw(resc,resv,argc,(mxArray**)(argv)); break; + case 2049: flag=_wrap_ITexture_width(resc,resv,argc,(mxArray**)(argv)); break; + case 2050: flag=_wrap_ITexture_height(resc,resv,argc,(mxArray**)(argv)); break; + case 2051: flag=_wrap_ITexture_setSubDrawArea(resc,resv,argc,(mxArray**)(argv)); break; + case 2052: flag=_wrap_VisualizerOptions_verbose_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2053: flag=_wrap_VisualizerOptions_verbose_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2054: flag=_wrap_VisualizerOptions_winWidth_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2055: flag=_wrap_VisualizerOptions_winWidth_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2056: flag=_wrap_VisualizerOptions_winHeight_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2057: flag=_wrap_VisualizerOptions_winHeight_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2058: flag=_wrap_VisualizerOptions_rootFrameArrowsDimension_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2059: flag=_wrap_VisualizerOptions_rootFrameArrowsDimension_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2060: flag=_wrap_new_VisualizerOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 2061: flag=_wrap_delete_VisualizerOptions(resc,resv,argc,(mxArray**)(argv)); break; + case 2062: flag=_wrap_delete_ITexturesHandler(resc,resv,argc,(mxArray**)(argv)); break; + case 2063: flag=_wrap_ITexturesHandler_add(resc,resv,argc,(mxArray**)(argv)); break; + case 2064: flag=_wrap_ITexturesHandler_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2065: flag=_wrap_new_Visualizer(resc,resv,argc,(mxArray**)(argv)); break; + case 2066: flag=_wrap_delete_Visualizer(resc,resv,argc,(mxArray**)(argv)); break; + case 2067: flag=_wrap_Visualizer_init(resc,resv,argc,(mxArray**)(argv)); break; + case 2068: flag=_wrap_Visualizer_getNrOfVisualizedModels(resc,resv,argc,(mxArray**)(argv)); break; + case 2069: flag=_wrap_Visualizer_getModelInstanceName(resc,resv,argc,(mxArray**)(argv)); break; + case 2070: flag=_wrap_Visualizer_getModelInstanceIndex(resc,resv,argc,(mxArray**)(argv)); break; + case 2071: flag=_wrap_Visualizer_addModel(resc,resv,argc,(mxArray**)(argv)); break; + case 2072: flag=_wrap_Visualizer_modelViz(resc,resv,argc,(mxArray**)(argv)); break; + case 2073: flag=_wrap_Visualizer_camera(resc,resv,argc,(mxArray**)(argv)); break; + case 2074: flag=_wrap_Visualizer_enviroment(resc,resv,argc,(mxArray**)(argv)); break; + case 2075: flag=_wrap_Visualizer_environment(resc,resv,argc,(mxArray**)(argv)); break; + case 2076: flag=_wrap_Visualizer_vectors(resc,resv,argc,(mxArray**)(argv)); break; + case 2077: flag=_wrap_Visualizer_frames(resc,resv,argc,(mxArray**)(argv)); break; + case 2078: flag=_wrap_Visualizer_textures(resc,resv,argc,(mxArray**)(argv)); break; + case 2079: flag=_wrap_Visualizer_getLabel(resc,resv,argc,(mxArray**)(argv)); break; + case 2080: flag=_wrap_Visualizer_width(resc,resv,argc,(mxArray**)(argv)); break; + case 2081: flag=_wrap_Visualizer_height(resc,resv,argc,(mxArray**)(argv)); break; + case 2082: flag=_wrap_Visualizer_run(resc,resv,argc,(mxArray**)(argv)); break; + case 2083: flag=_wrap_Visualizer_draw(resc,resv,argc,(mxArray**)(argv)); break; + case 2084: flag=_wrap_Visualizer_subDraw(resc,resv,argc,(mxArray**)(argv)); break; + case 2085: flag=_wrap_Visualizer_drawToFile(resc,resv,argc,(mxArray**)(argv)); break; + case 2086: flag=_wrap_Visualizer_close(resc,resv,argc,(mxArray**)(argv)); break; + case 2087: flag=_wrap_Visualizer_isWindowActive(resc,resv,argc,(mxArray**)(argv)); break; + case 2088: flag=_wrap_Visualizer_setColorPalette(resc,resv,argc,(mxArray**)(argv)); break; + case 2089: flag=_wrap_Polygon_m_vertices_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2090: flag=_wrap_Polygon_m_vertices_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2091: flag=_wrap_new_Polygon(resc,resv,argc,(mxArray**)(argv)); break; + case 2092: flag=_wrap_Polygon_setNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; + case 2093: flag=_wrap_Polygon_getNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; + case 2094: flag=_wrap_Polygon_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 2095: flag=_wrap_Polygon_applyTransform(resc,resv,argc,(mxArray**)(argv)); break; + case 2096: flag=_wrap_Polygon_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 2097: flag=_wrap_Polygon_XYRectangleFromOffsets(resc,resv,argc,(mxArray**)(argv)); break; + case 2098: flag=_wrap_delete_Polygon(resc,resv,argc,(mxArray**)(argv)); break; + case 2099: flag=_wrap_Polygon2D_m_vertices_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2100: flag=_wrap_Polygon2D_m_vertices_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2101: flag=_wrap_new_Polygon2D(resc,resv,argc,(mxArray**)(argv)); break; + case 2102: flag=_wrap_Polygon2D_setNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; + case 2103: flag=_wrap_Polygon2D_getNrOfVertices(resc,resv,argc,(mxArray**)(argv)); break; + case 2104: flag=_wrap_Polygon2D_isValid(resc,resv,argc,(mxArray**)(argv)); break; + case 2105: flag=_wrap_Polygon2D_paren(resc,resv,argc,(mxArray**)(argv)); break; + case 2106: flag=_wrap_delete_Polygon2D(resc,resv,argc,(mxArray**)(argv)); break; + case 2107: flag=_wrap_ConvexHullProjectionConstraint_setActive(resc,resv,argc,(mxArray**)(argv)); break; + case 2108: flag=_wrap_ConvexHullProjectionConstraint_isActive(resc,resv,argc,(mxArray**)(argv)); break; + case 2109: flag=_wrap_ConvexHullProjectionConstraint_getNrOfConstraints(resc,resv,argc,(mxArray**)(argv)); break; + case 2110: flag=_wrap_ConvexHullProjectionConstraint_projectedConvexHull_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2111: flag=_wrap_ConvexHullProjectionConstraint_projectedConvexHull_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2112: flag=_wrap_ConvexHullProjectionConstraint_A_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2113: flag=_wrap_ConvexHullProjectionConstraint_A_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2114: flag=_wrap_ConvexHullProjectionConstraint_b_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2115: flag=_wrap_ConvexHullProjectionConstraint_b_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2116: flag=_wrap_ConvexHullProjectionConstraint_P_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2117: flag=_wrap_ConvexHullProjectionConstraint_P_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2118: flag=_wrap_ConvexHullProjectionConstraint_Pdirection_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2119: flag=_wrap_ConvexHullProjectionConstraint_Pdirection_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2120: flag=_wrap_ConvexHullProjectionConstraint_AtimesP_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2121: flag=_wrap_ConvexHullProjectionConstraint_AtimesP_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2122: flag=_wrap_ConvexHullProjectionConstraint_o_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2123: flag=_wrap_ConvexHullProjectionConstraint_o_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2124: flag=_wrap_ConvexHullProjectionConstraint_buildConvexHull(resc,resv,argc,(mxArray**)(argv)); break; + case 2125: flag=_wrap_ConvexHullProjectionConstraint_supportFrameIndices_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2126: flag=_wrap_ConvexHullProjectionConstraint_supportFrameIndices_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2127: flag=_wrap_ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_get(resc,resv,argc,(mxArray**)(argv)); break; + case 2128: flag=_wrap_ConvexHullProjectionConstraint_absoluteFrame_X_supportFrame_set(resc,resv,argc,(mxArray**)(argv)); break; + case 2129: flag=_wrap_ConvexHullProjectionConstraint_project(resc,resv,argc,(mxArray**)(argv)); break; + case 2130: flag=_wrap_ConvexHullProjectionConstraint_computeMargin(resc,resv,argc,(mxArray**)(argv)); break; + case 2131: flag=_wrap_ConvexHullProjectionConstraint_setProjectionAlongDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 2132: flag=_wrap_ConvexHullProjectionConstraint_projectAlongDirection(resc,resv,argc,(mxArray**)(argv)); break; + case 2133: flag=_wrap_new_ConvexHullProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2134: flag=_wrap_delete_ConvexHullProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2135: flag=_wrap_sizeOfRotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; + case 2136: flag=_wrap_new_InverseKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 2137: flag=_wrap_delete_InverseKinematics(resc,resv,argc,(mxArray**)(argv)); break; + case 2138: flag=_wrap_InverseKinematics_loadModelFromFile(resc,resv,argc,(mxArray**)(argv)); break; + case 2139: flag=_wrap_InverseKinematics_setModel(resc,resv,argc,(mxArray**)(argv)); break; + case 2140: flag=_wrap_InverseKinematics_setJointLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 2141: flag=_wrap_InverseKinematics_getJointLimits(resc,resv,argc,(mxArray**)(argv)); break; + case 2142: flag=_wrap_InverseKinematics_clearProblem(resc,resv,argc,(mxArray**)(argv)); break; + case 2143: flag=_wrap_InverseKinematics_setFloatingBaseOnFrameNamed(resc,resv,argc,(mxArray**)(argv)); break; + case 2144: flag=_wrap_InverseKinematics_setCurrentRobotConfiguration(resc,resv,argc,(mxArray**)(argv)); break; + case 2145: flag=_wrap_InverseKinematics_setJointConfiguration(resc,resv,argc,(mxArray**)(argv)); break; + case 2146: flag=_wrap_InverseKinematics_setRotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; + case 2147: flag=_wrap_InverseKinematics_rotationParametrization(resc,resv,argc,(mxArray**)(argv)); break; + case 2148: flag=_wrap_InverseKinematics_setMaxIterations(resc,resv,argc,(mxArray**)(argv)); break; + case 2149: flag=_wrap_InverseKinematics_maxIterations(resc,resv,argc,(mxArray**)(argv)); break; + case 2150: flag=_wrap_InverseKinematics_setMaxCPUTime(resc,resv,argc,(mxArray**)(argv)); break; + case 2151: flag=_wrap_InverseKinematics_maxCPUTime(resc,resv,argc,(mxArray**)(argv)); break; + case 2152: flag=_wrap_InverseKinematics_setCostTolerance(resc,resv,argc,(mxArray**)(argv)); break; + case 2153: flag=_wrap_InverseKinematics_costTolerance(resc,resv,argc,(mxArray**)(argv)); break; + case 2154: flag=_wrap_InverseKinematics_setConstraintsTolerance(resc,resv,argc,(mxArray**)(argv)); break; + case 2155: flag=_wrap_InverseKinematics_constraintsTolerance(resc,resv,argc,(mxArray**)(argv)); break; + case 2156: flag=_wrap_InverseKinematics_setVerbosity(resc,resv,argc,(mxArray**)(argv)); break; + case 2157: flag=_wrap_InverseKinematics_linearSolverName(resc,resv,argc,(mxArray**)(argv)); break; + case 2158: flag=_wrap_InverseKinematics_setLinearSolverName(resc,resv,argc,(mxArray**)(argv)); break; + case 2159: flag=_wrap_InverseKinematics_addFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2160: flag=_wrap_InverseKinematics_addFramePositionConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2161: flag=_wrap_InverseKinematics_addFrameRotationConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2162: flag=_wrap_InverseKinematics_activateFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2163: flag=_wrap_InverseKinematics_deactivateFrameConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2164: flag=_wrap_InverseKinematics_isFrameConstraintActive(resc,resv,argc,(mxArray**)(argv)); break; + case 2165: flag=_wrap_InverseKinematics_addCenterOfMassProjectionConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2166: flag=_wrap_InverseKinematics_getCenterOfMassProjectionMargin(resc,resv,argc,(mxArray**)(argv)); break; + case 2167: flag=_wrap_InverseKinematics_getCenterOfMassProjectConstraintConvexHull(resc,resv,argc,(mxArray**)(argv)); break; + case 2168: flag=_wrap_InverseKinematics_addTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2169: flag=_wrap_InverseKinematics_addPositionTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2170: flag=_wrap_InverseKinematics_addRotationTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2171: flag=_wrap_InverseKinematics_updateTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2172: flag=_wrap_InverseKinematics_updatePositionTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2173: flag=_wrap_InverseKinematics_updateRotationTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2174: flag=_wrap_InverseKinematics_setDefaultTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; + case 2175: flag=_wrap_InverseKinematics_defaultTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; + case 2176: flag=_wrap_InverseKinematics_setTargetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; + case 2177: flag=_wrap_InverseKinematics_targetResolutionMode(resc,resv,argc,(mxArray**)(argv)); break; + case 2178: flag=_wrap_InverseKinematics_setDesiredFullJointsConfiguration(resc,resv,argc,(mxArray**)(argv)); break; + case 2179: flag=_wrap_InverseKinematics_setDesiredReducedJointConfiguration(resc,resv,argc,(mxArray**)(argv)); break; + case 2180: flag=_wrap_InverseKinematics_setFullJointsInitialCondition(resc,resv,argc,(mxArray**)(argv)); break; + case 2181: flag=_wrap_InverseKinematics_setReducedInitialCondition(resc,resv,argc,(mxArray**)(argv)); break; + case 2182: flag=_wrap_InverseKinematics_solve(resc,resv,argc,(mxArray**)(argv)); break; + case 2183: flag=_wrap_InverseKinematics_getFullJointsSolution(resc,resv,argc,(mxArray**)(argv)); break; + case 2184: flag=_wrap_InverseKinematics_getReducedSolution(resc,resv,argc,(mxArray**)(argv)); break; + case 2185: flag=_wrap_InverseKinematics_getPoseForFrame(resc,resv,argc,(mxArray**)(argv)); break; + case 2186: flag=_wrap_InverseKinematics_fullModel(resc,resv,argc,(mxArray**)(argv)); break; + case 2187: flag=_wrap_InverseKinematics_reducedModel(resc,resv,argc,(mxArray**)(argv)); break; + case 2188: flag=_wrap_InverseKinematics_setCOMTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2189: flag=_wrap_InverseKinematics_setCOMAsConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2190: flag=_wrap_InverseKinematics_setCOMAsConstraintTolerance(resc,resv,argc,(mxArray**)(argv)); break; + case 2191: flag=_wrap_InverseKinematics_isCOMAConstraint(resc,resv,argc,(mxArray**)(argv)); break; + case 2192: flag=_wrap_InverseKinematics_isCOMTargetActive(resc,resv,argc,(mxArray**)(argv)); break; + case 2193: flag=_wrap_InverseKinematics_deactivateCOMTarget(resc,resv,argc,(mxArray**)(argv)); break; + case 2194: flag=_wrap_InverseKinematics_setCOMConstraintProjectionDirection(resc,resv,argc,(mxArray**)(argv)); break; default: flag=1, SWIG_Error(SWIG_RuntimeError, "No function id %d.", fcn_id); } if (flag) { From 0e146f61179e55a1445c97d9fd24f96e1143ed72 Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sat, 14 Oct 2023 17:59:38 +0200 Subject: [PATCH 8/8] Remove use of raw classes in InertiaUnitTest.m --- bindings/matlab/tests/InertiaUnitTest.m | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bindings/matlab/tests/InertiaUnitTest.m b/bindings/matlab/tests/InertiaUnitTest.m index fe6ec900a3..2943a53c22 100644 --- a/bindings/matlab/tests/InertiaUnitTest.m +++ b/bindings/matlab/tests/InertiaUnitTest.m @@ -17,7 +17,7 @@ twistInFrame1.setVal(4,twistInFrame1_m(5)); twistInFrame1.setVal(5,twistInFrame1_m(6)); - angularInertia = iDynTree.RotationalInertiaRaw(); + angularInertia = iDynTree.RotationalInertia(); angularInertia.setVal(0,0,1.0); angularInertia.setVal(1,1,2.0); angularInertia.setVal(2,2,3.0);