iDynTree::KinDynComputations class

High level stateful class wrapping several kinematics and dynamics algorithms.

The kinematics dynamics computations class is an high level class stateful to access several algorithms related to kinematics and dynamics of free floating robot systems.

This class supports three possible convention to express the floating base information : the inertial, the body-fixed and the mixed convention. To get more info on this three conventions, check section II.C of On the Base Frame Choice in Free-Floating Mechanical Systems and its Connection to Centroidal Dynamics https://traversaro.github.io/preprints/changebase.pdf

Constructor/Destructor

KinDynComputations()
Constructor.
~KinDynComputations() virtual
Destructor.

Model loading and definition methods

This methods are used to load the structure of your model.

auto loadRobotModel(const iDynTree::Model& model) -> bool
Load the model of the robot from a iDynTree::Model class.
auto isValid() const -> bool
Return true if the models for the robot have been correctly.
auto setFrameVelocityRepresentation(const FrameVelocityRepresentation frameVelRepr) const -> bool
Set the used FrameVelocityRepresentation.
auto getFrameVelocityRepresentation() const -> FrameVelocityRepresentation
Get the used FrameVelocityRepresentation.
auto getNrOfDegreesOfFreedom() const -> unsigned int
Get the number of internal degrees of freedom of the robot model used in the class.
auto getDescriptionOfDegreeOfFreedom(int dof_index) const -> std::string
Get a human readable description of a given internal degree of freedom of the robot.
auto getDescriptionOfDegreesOfFreedom() const -> std::string
Get a human readable description of all the internal degrees of freedom of the robot.
auto getNrOfLinks() const -> unsigned int
Get the number of links contained in the model.
auto getNrOfFrames() const -> unsigned int
Get the number of frames contained in the model.
auto getFloatingBase() const -> std::string
Get the name of the link considered as the floating base.
auto setFloatingBase(const std::string& floatingBaseName) -> bool
Set the link that is used as the floating base link.

Methods to access the underlyng model for the robot

auto model() const -> const Model&
auto getRobotModel() const -> const Model&

Methods to obtain the sparity patterns of Jacobians and Hessians

auto getRelativeJacobianSparsityPattern(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobianPattern) const -> bool
Returns the sparsity pattern of the relative Jacobian for the specified frames.
auto getRelativeJacobianSparsityPattern(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobianPattern) const -> bool
Returns the sparsity pattern of the relative Jacobian for the specified frames (MatrixView implementation)
auto getFrameFreeFloatingJacobianSparsityPattern(const FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobianPattern) const -> bool
Returns the sparsity pattern of the free floating Jacobian for the specified frame.
auto getFrameFreeFloatingJacobianSparsityPattern(const FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobianPattern) const -> bool
Returns the sparsity pattern of the free floating Jacobian for the specified frame (MatrixView implementation).

Methods to submit the input data for dynamics computations.

auto setJointPos(const iDynTree::VectorDynSize& s) -> bool
Set the (internal) joint positions.
auto setJointPos(iDynTree::Span<const double> s) -> bool
Set the (internal) joint positions.
auto setWorldBaseTransform(const iDynTree::Transform& world_T_base) -> bool
Set the world base transform.
auto setWorldBaseTransform(iDynTree::MatrixView<const double>& world_T_base) -> bool
Set the world base transform (MatrixView implementation).
auto setRobotState(const iDynTree::Transform& world_T_base, const iDynTree::VectorDynSize& s, const iDynTree::Twist& base_velocity, const iDynTree::VectorDynSize& s_dot, const iDynTree::Vector3& world_gravity) -> bool
Set the state for the robot (floating base)
auto setRobotState(iDynTree::MatrixView<const double> world_T_base, iDynTree::Span<const double> s, iDynTree::Span<const double> base_velocity, iDynTree::Span<const double> s_dot, iDynTree::Span<const double> world_gravity) -> bool
Set the state for the robot (floating base) (Span and MatrixView implementation)
auto setRobotState(const iDynTree::VectorDynSize& s, const iDynTree::VectorDynSize& s_dot, const iDynTree::Vector3& world_gravity) -> bool
Set the state for the robot (fixed base) Same as setRobotState, but with: world_T_base = iDynTree::Transform::Identity() base_velocity = iDynTree::Twist::Zero();.
auto setRobotState(iDynTree::Span<const double> s, iDynTree::Span<const double> s_dot, iDynTree::Span<const double> world_gravity) -> bool
Set the state for the robot (fixed base) Same as setRobotState, but with: world_T_base = iDynTree::Transform::Identity() base_velocity = iDynTree::Twist::Zero();.
void getRobotState(iDynTree::Transform& world_T_base, iDynTree::VectorDynSize& s, iDynTree::Twist& base_velocity, iDynTree::VectorDynSize& s_dot, iDynTree::Vector3& world_gravity)
void getRobotState(iDynTree::VectorDynSize& s, iDynTree::VectorDynSize& s_dot, iDynTree::Vector3& world_gravity)
auto getRobotState(iDynTree::MatrixView<double> world_T_base, iDynTree::Span<double> s, iDynTree::Span<double> base_velocity, iDynTree::Span<double> s_dot, iDynTree::Span<double> world_gravity) -> bool
void getRobotState(iDynTree::Span<double> s, iDynTree::Span<double> s_dot, iDynTree::Span<double> world_gravity)
auto getWorldBaseTransform() const -> iDynTree::Transform
Access the robot state.
auto getWorldBaseTransform(iDynTree::MatrixView<double> world_T_base) const -> bool
auto getBaseTwist() const -> iDynTree::Twist
auto getBaseTwist(iDynTree::Span<double> base_velocity) const -> bool
auto getJointPos(iDynTree::VectorDynSize& q) const -> bool
auto getJointPos(iDynTree::Span<double> q) const -> bool
Get the n joint position of the model.
auto getJointVel(iDynTree::VectorDynSize& dq) const -> bool
auto getJointVel(iDynTree::Span<double> dq) const -> bool
Get the n joint velocity of the model.
auto getModelVel(iDynTree::VectorDynSize& nu) const -> bool
Get the n+6 velocity of the model.
auto getModelVel(iDynTree::Span<double> nu) const -> bool
Get the n+6 velocity of the model.

Methods to get transform information between frames in the model, given the current state.

auto getFrameIndex(const std::string& frameName) const -> int
Get the index corresponding to a given frame name.
auto getFrameName(const iDynTree::FrameIndex frameIndex) const -> std::string
Get the frame name corresponding to a given frame index.
auto getWorldTransform(const iDynTree::FrameIndex frameIndex) -> iDynTree::Transform
Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the world one (world_H_frame).
auto getWorldTransform(const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> world_T_frame) -> bool
Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the world one (world_T_frame).
auto getWorldTransform(const std::string& frameName) -> iDynTree::Transform
Version of getWorldTransform where the frame is specified by name.
auto getWorldTransform(const std::string& frameName, iDynTree::MatrixView<double> world_T_frame) -> bool
Version of getWorldTransform where the frame is specified by name (MatrixView and Span implementation).
auto getWorldTransformsAsHomogeneous(const std::vector<std::string>& frameNames) -> std::vector<iDynTree::Matrix4x4>
Return the transforms as a homogeneous matrices where the frame is specified by name in the frameNames vector, and the reference frame is the world one (world_H_frame).
auto getRelativeTransform(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex) -> iDynTree::Transform
Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the one specified by refFrameIndex (refFrame_H_frame).
auto getRelativeTransform(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> refFrame_H_frame) -> bool
Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the one specified by refFrameIndex (refFrame_H_frame).
auto getRelativeTransformExplicit(const iDynTree::FrameIndex refFrameOriginIndex, const iDynTree::FrameIndex refFrameOrientationIndex, const iDynTree::FrameIndex frameOriginIndex, const iDynTree::FrameIndex frameOrientationIndex) -> iDynTree::Transform
Return the transform between the frame with the origin of the frameOriginIndex and the orientation of frameOrientationIndex and the one with the origin of refFrameOriginIndex and the orientation of refFrameOrientationIndex .
auto getRelativeTransformExplicit(const iDynTree::FrameIndex refFrameOriginIndex, const iDynTree::FrameIndex refFrameOrientationIndex, const iDynTree::FrameIndex frameOriginIndex, const iDynTree::FrameIndex frameOrientationIndex, iDynTree::MatrixView<double> refFrameOrigin_refFrameOrientation_H_frameOrigin_frameORientation) -> bool
Return the transform between the frame with the origin of the frameOriginIndex and the orientation of frameOrientationIndex and the one with the origin of refFrameOriginIndex and the orientation of refFrameOrientationIndex.
auto getRelativeTransform(const std::string& refFrameName, const std::string& frameName) -> iDynTree::Transform
Version of getRelativeTransform where the frames are specified by name.
auto getRelativeTransform(const std::string& refFrameName, const std::string& frameName, iDynTree::MatrixView<double> refFrame_H_frame) -> bool
Version of getRelativeTransform where the frames are specified by name (Span and MatrixView version).

Methods to get frame velocity information given the current state.

auto getFrameVel(const std::string& frameName) -> iDynTree::Twist
Return the frame velocity, with the convention specified by getFrameVelocityRepresentation.
auto getFrameVel(const std::string& frameName, iDynTree::Span<double> twist) -> bool
Return the frame velocity, with the convention specified by getFrameVelocityRepresentation.
auto getFrameVel(const FrameIndex frameIdx) -> iDynTree::Twist
Return the frame velocity, with the convention specified by getFrameVelocityRepresentation .
auto getFrameVel(const FrameIndex frameIdx, iDynTree::Span<double> twist) -> bool
Return the frame velocity, with the convention specified by getFrameVelocityRepresentation.
auto getFrameAcc(const std::string& frameName, const Vector6& baseAcc, const VectorDynSize& s_ddot) -> Vector6
Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation .
auto getFrameAcc(const std::string& frameName, iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, iDynTree::Span<double> frame_acceleration) -> bool
Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation.
auto getFrameAcc(const FrameIndex frameIdx, const Vector6& baseAcc, const VectorDynSize& s_ddot) -> Vector6
Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation .
auto getFrameAcc(const FrameIndex frameName, iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, iDynTree::Span<double> frame_acceleration) -> bool
Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation.
auto getFrameFreeFloatingJacobian(const std::string& frameName, iDynTree::MatrixDynSize& outJacobian) -> bool
Compute the free floating jacobian for a given frame for the given representaiton.
auto getFrameFreeFloatingJacobian(const FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobian) -> bool
Compute the free floating jacobian for a given frame for the given representaiton.
auto getFrameFreeFloatingJacobian(const std::string& frameName, iDynTree::MatrixView<double> outJacobian) -> bool
Compute the free floating jacobian for a given frame for the given representaiton (MatrixView implementation).
auto getFrameFreeFloatingJacobian(const FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobian) -> bool
Compute the free floating jacobian for a given frame for the given representaiton (MatrixView implementation).
auto getRelativeJacobian(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobian) -> bool
Return the relative Jacobian between the two frames.
auto getRelativeJacobian(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobian) -> bool
Return the relative Jacobian between the two frames (MatrixView implementation).
auto getRelativeJacobianExplicit(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, const iDynTree::FrameIndex expressedOriginFrameIndex, const iDynTree::FrameIndex expressedOrientationFrameIndex, iDynTree::MatrixDynSize& outJacobian) -> bool
Return the relative Jacobian between the two frames.
auto getRelativeJacobianExplicit(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, const iDynTree::FrameIndex expressedOriginFrameIndex, const iDynTree::FrameIndex expressedOrientationFrameIndex, iDynTree::MatrixView<double> outJacobian) -> bool
Return the relative Jacobian between the two frames (MatrixView implementation)
auto getFrameBiasAcc(const FrameIndex frameIdx) -> Vector6
Get the bias acceleration (i.e.
auto getFrameBiasAcc(const FrameIndex frameIdx, iDynTree::Span<double> bias_acc) -> bool
Get the bias acceleration (i.e.
auto getFrameBiasAcc(const std::string& frameName) -> Vector6
Get the bias acceleration (i.e.
auto getFrameBiasAcc(const std::string& frameName, iDynTree::Span<double> bias_acc) -> bool
Get the bias acceleration (i.e.

Function documentation

bool iDynTree::KinDynComputations::loadRobotModel(const iDynTree::Model& model)

Load the model of the robot from a iDynTree::Model class.

Parameters
model the model to use in this class.
Returns true if all went ok, false otherwise.

bool iDynTree::KinDynComputations::isValid() const

Return true if the models for the robot have been correctly.

Returns True if the class has been correctly configure, false otherwise.

bool iDynTree::KinDynComputations::setFrameVelocityRepresentation(const FrameVelocityRepresentation frameVelRepr) const

Set the used FrameVelocityRepresentation.

FrameVelocityRepresentation iDynTree::KinDynComputations::getFrameVelocityRepresentation() const

Get the used FrameVelocityRepresentation.

unsigned int iDynTree::KinDynComputations::getNrOfDegreesOfFreedom() const

Get the number of internal degrees of freedom of the robot model used in the class.

Returns the number of internal degrees of freedom of the model.

This return the internal degrees of freedom, because it does not include the eventual 6 degrees of freedom usually associated with the floating base.

std::string iDynTree::KinDynComputations::getDescriptionOfDegreesOfFreedom() const

Get a human readable description of all the internal degrees of freedom of the robot.

Returns a std::string containing the description of the internal degrees of freedom.

unsigned int iDynTree::KinDynComputations::getNrOfFrames() const

Get the number of frames contained in the model.

std::string iDynTree::KinDynComputations::getFloatingBase() const

Get the name of the link considered as the floating base.

Returns the name of the base link.

bool iDynTree::KinDynComputations::setFloatingBase(const std::string& floatingBaseName)

Set the link that is used as the floating base link.

Returns true if all went well, false otherwise (for example if the link name was not found).

Currently supports only links. See https://github.com/robotology/idyntree/issues/422.

bool iDynTree::KinDynComputations::getRelativeJacobianSparsityPattern(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobianPattern) const

Returns the sparsity pattern of the relative Jacobian for the specified frames.

Parameters
refFrameIndex refence frame for the Jacobian
frameIndex Jacobian frame
outJacobianPattern the Jacobian sparsity pattern
Returns true on success. False otherwise

The resulting matrix has the same size of the free floating Jacobian (6 x #DoFs) It is filled with only 0 and 1 with the following meaning:

  • 0: the element will always have 0 (for every robot configuration)
  • 1: it exists a robot configuration such that the element have a value different from zero.

bool iDynTree::KinDynComputations::getRelativeJacobianSparsityPattern(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobianPattern) const

Returns the sparsity pattern of the relative Jacobian for the specified frames (MatrixView implementation)

Parameters
refFrameIndex refence frame for the Jacobian
frameIndex Jacobian frame
outJacobianPattern a MatrixView containing an already existing memory.
Returns true on success. False otherwise

The resulting matrix must have the same size of the free floating Jacobian (6 x #DoFs) It is filled with only 0 and 1 with the following meaning:

  • 0: the element will always have 0 (for every robot configuration)
  • 1: it exists a robot configuration such that the element have a value different from zero.

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobianSparsityPattern(const FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobianPattern) const

Returns the sparsity pattern of the free floating Jacobian for the specified frame.

Parameters
frameIndex Jacobian frame
outJacobianPattern the Jacobian sparsity pattern
Returns true on success. False otherwise

The resulting matrix has the same size of the free floating Jacobian (6 x 6 + #DoFs) It is filled with only 0 and 1 with the following meaning:

  • 0: the element will always have 0 (for every robot configuration)
  • 1: it exists a robot configuration such that the element have a value different from zero.

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobianSparsityPattern(const FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobianPattern) const

Returns the sparsity pattern of the free floating Jacobian for the specified frame (MatrixView implementation).

Parameters
frameIndex Jacobian frame
outJacobianPattern the Jacobian sparsity pattern
Returns true on success. False otherwise

The resulting matrix has the same size of the free floating Jacobian (6 x (6 + #DoFs)) It is filled with only 0 and 1 with the following meaning:

  • 0: the element will always have 0 (for every robot configuration)
  • 1: it exists a robot configuration such that the element have a value different from zero.

bool iDynTree::KinDynComputations::setJointPos(const iDynTree::VectorDynSize& s)

Set the (internal) joint positions.

Parameters
in A vector of dimension this->model().getNrOfPosCoords() .
Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::setJointPos(iDynTree::Span<const double> s)

Set the (internal) joint positions.

Parameters
in A vector of dimension this->model().getNrOfPosCoords() .
Returns true if all went well, false otherwise.

(Span implementation)

bool iDynTree::KinDynComputations::setWorldBaseTransform(const iDynTree::Transform& world_T_base)

Set the world base transform.

Parameters
world_T_base in the homogeneous transformation that transforms position vectors expressed in the base reference frame in position frames expressed in the world reference frame (i.e. pos_world = world_T_base*pos_base .
Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::setWorldBaseTransform(iDynTree::MatrixView<const double>& world_T_base)

Set the world base transform (MatrixView implementation).

Parameters
world_T_base in the homogeneous transformation that transforms position vectors expressed in the base reference frame in position frames expressed in the world reference frame (i.e. pos_world = world_T_base*pos_base .
Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::setRobotState(const iDynTree::Transform& world_T_base, const iDynTree::VectorDynSize& s, const iDynTree::Twist& base_velocity, const iDynTree::VectorDynSize& s_dot, const iDynTree::Vector3& world_gravity)

Set the state for the robot (floating base)

Parameters
world_T_base the homogeneous transformation that transforms position vectors expressed in the base reference frame in position frames expressed in the world reference frame (i.e. pos_world = world_T_base*pos_base .
s a vector of getNrOfDegreesOfFreedom() joint positions (in rad)
base_velocity The twist (linear/angular velocity) of the base, expressed with the convention specified by the used FrameVelocityConvention.
s_dot a vector of getNrOfDegreesOfFreedom() joint velocities (in rad/sec)
world_gravity a 3d vector of the gravity acceleration vector, expressed in the world/inertial frame.
Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::setRobotState(iDynTree::MatrixView<const double> world_T_base, iDynTree::Span<const double> s, iDynTree::Span<const double> base_velocity, iDynTree::Span<const double> s_dot, iDynTree::Span<const double> world_gravity)

Set the state for the robot (floating base) (Span and MatrixView implementation)

Parameters
world_T_base the 4x4 homogeneous transformation that transforms position vectors expressed in the base reference frame in position frames expressed in the world reference frame (i.e. pos_world = world_T_base*pos_base).
s a vector of getNrOfDegreesOfFreedom() joint positions (in rad)
base_velocity The twist (linear/angular velocity) of the base, expressed with the convention specified by the used FrameVelocityConvention.
s_dot a vector of getNrOfDegreesOfFreedom() joint velocities (in rad/sec)
world_gravity a 3d vector of the gravity acceleration vector, expressed in the world/inertial frame.
Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::setRobotState(iDynTree::Span<const double> s, iDynTree::Span<const double> s_dot, iDynTree::Span<const double> world_gravity)

Set the state for the robot (fixed base) Same as setRobotState, but with: world_T_base = iDynTree::Transform::Identity() base_velocity = iDynTree::Twist::Zero();.

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getJointPos(iDynTree::Span<double> q) const

Get the n joint position of the model.

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getJointVel(iDynTree::Span<double> dq) const

Get the n joint velocity of the model.

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getModelVel(iDynTree::VectorDynSize& nu) const

Get the n+6 velocity of the model.

Obtained by stacking the output of getBaseTwist and of getJointVel.

bool iDynTree::KinDynComputations::getModelVel(iDynTree::Span<double> nu) const

Get the n+6 velocity of the model.

Returns true if all went well, false otherwise.

Obtained by stacking the output of getBaseTwist and of getJointVel.

int iDynTree::KinDynComputations::getFrameIndex(const std::string& frameName) const

Get the index corresponding to a given frame name.

Returns a integer greater than or equal to zero if the frame exist, a negative integer otherwise.

bool iDynTree::KinDynComputations::getWorldTransform(const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> world_T_frame)

Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the world one (world_T_frame).

Parameters
frameIndex
world_T_frame a 4x4 matrix representing the homogeneous transformation that transforms position vectors expressed in the 'frame' reference frame in position frames expressed in the world reference frame (i.e. pos_world = world_T_frame * pos_frame).
Returns true if all went well, false otherwise.

iDynTree::Transform iDynTree::KinDynComputations::getWorldTransform(const std::string& frameName)

Version of getWorldTransform where the frame is specified by name.

bool iDynTree::KinDynComputations::getWorldTransform(const std::string& frameName, iDynTree::MatrixView<double> world_T_frame)

Version of getWorldTransform where the frame is specified by name (MatrixView and Span implementation).

bool iDynTree::KinDynComputations::getRelativeTransform(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> refFrame_H_frame)

Return the transform where the frame is the frame specified by frameIndex, and the reference frame is the one specified by refFrameIndex (refFrame_H_frame).

Parameters
refFrameIndex
frameIndex
refFrame_H_frame a 4x4 matrix representing the homogeneous transformation that transforms position vectors expressed in the 'frame' reference frame in position frames expressed in the 'refFrame' reference frame (i.e. pos_refFrame = refFrame_T_frame * pos_frame).
Returns true if all went well, false otherwise.

iDynTree::Transform iDynTree::KinDynComputations::getRelativeTransformExplicit(const iDynTree::FrameIndex refFrameOriginIndex, const iDynTree::FrameIndex refFrameOrientationIndex, const iDynTree::FrameIndex frameOriginIndex, const iDynTree::FrameIndex frameOrientationIndex)

Return the transform between the frame with the origin of the frameOriginIndex and the orientation of frameOrientationIndex and the one with the origin of refFrameOriginIndex and the orientation of refFrameOrientationIndex .

In symbols we return the (refFrameOrigin,refFrameOrientation)_H_(frameOrigin,frameORientation)

This is a variant of the getRelativeTransform in which the orientation and origin part of both side of the transform are explicited.

bool iDynTree::KinDynComputations::getRelativeTransformExplicit(const iDynTree::FrameIndex refFrameOriginIndex, const iDynTree::FrameIndex refFrameOrientationIndex, const iDynTree::FrameIndex frameOriginIndex, const iDynTree::FrameIndex frameOrientationIndex, iDynTree::MatrixView<double> refFrameOrigin_refFrameOrientation_H_frameOrigin_frameORientation)

Return the transform between the frame with the origin of the frameOriginIndex and the orientation of frameOrientationIndex and the one with the origin of refFrameOriginIndex and the orientation of refFrameOrientationIndex.

(MatrixView and Span implementation)

In symbols we return the (refFrameOrigin,refFrameOrientation)_H_(frameOrigin,frameORientation)

This is a variant of the getRelativeTransform in which the orientation and origin part of both side of the transform are explicited.

iDynTree::Transform iDynTree::KinDynComputations::getRelativeTransform(const std::string& refFrameName, const std::string& frameName)

Version of getRelativeTransform where the frames are specified by name.

bool iDynTree::KinDynComputations::getRelativeTransform(const std::string& refFrameName, const std::string& frameName, iDynTree::MatrixView<double> refFrame_H_frame)

Version of getRelativeTransform where the frames are specified by name (Span and MatrixView version).

bool iDynTree::KinDynComputations::getFrameVel(const std::string& frameName, iDynTree::Span<double> twist)

Return the frame velocity, with the convention specified by getFrameVelocityRepresentation.

Returns true if all went well, false otherwise.

(MatrixView and Span implementation)

bool iDynTree::KinDynComputations::getFrameVel(const FrameIndex frameIdx, iDynTree::Span<double> twist)

Return the frame velocity, with the convention specified by getFrameVelocityRepresentation.

Returns true if all went well, false otherwise.

(MatrixView and Span implementation)

Vector6 iDynTree::KinDynComputations::getFrameAcc(const std::string& frameName, const Vector6& baseAcc, const VectorDynSize& s_ddot)

Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation .

bool iDynTree::KinDynComputations::getFrameAcc(const std::string& frameName, iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, iDynTree::Span<double> frame_acceleration)

Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation.

Returns true if all went well, false otherwise.

(Span version)

Vector6 iDynTree::KinDynComputations::getFrameAcc(const FrameIndex frameIdx, const Vector6& baseAcc, const VectorDynSize& s_ddot)

Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation .

bool iDynTree::KinDynComputations::getFrameAcc(const FrameIndex frameName, iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, iDynTree::Span<double> frame_acceleration)

Return the frame acceleration, with the convention specified by getFrameVelocityRepresentation.

Returns true if all went well, false otherwise.

(MatrixView and Span version)

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobian(const std::string& frameName, iDynTree::MatrixDynSize& outJacobian)

Compute the free floating jacobian for a given frame for the given representaiton.

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobian(const FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobian)

Compute the free floating jacobian for a given frame for the given representaiton.

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobian(const std::string& frameName, iDynTree::MatrixView<double> outJacobian)

Compute the free floating jacobian for a given frame for the given representaiton (MatrixView implementation).

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getFrameFreeFloatingJacobian(const FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobian)

Compute the free floating jacobian for a given frame for the given representaiton (MatrixView implementation).

Returns true if all went well, false otherwise.

bool iDynTree::KinDynComputations::getRelativeJacobian(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixDynSize& outJacobian)

Return the relative Jacobian between the two frames.

The Jacobian maps the internal robot shape with the relative velocity of refFrame w.r.t. frame expressed depending on the velocity representation, i.e

\[ v_{refFrame, frame} = J_{refFrame, frame}(s) \dot{s} \]

bool iDynTree::KinDynComputations::getRelativeJacobian(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, iDynTree::MatrixView<double> outJacobian)

Return the relative Jacobian between the two frames (MatrixView implementation).

Returns true if all went well, false otherwise.

The Jacobian maps the internal robot shape with the relative velocity of refFrame w.r.t. frame expressed depending on the velocity representation, i.e

\[ v_{refFrame, frame} = J_{refFrame, frame}(s) \dot{s} \]

bool iDynTree::KinDynComputations::getRelativeJacobianExplicit(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, const iDynTree::FrameIndex expressedOriginFrameIndex, const iDynTree::FrameIndex expressedOrientationFrameIndex, iDynTree::MatrixDynSize& outJacobian)

Return the relative Jacobian between the two frames.

Parameters
refFrameIndex reference frame
frameIndex considered frame
expressedOriginFrameIndex frame whose origin is used to express the Jacobian
expressedOrientationFrameIndex frame whose orientation is used to express the Jacobian
outJacobian
Returns true on success, false otherwise

The Jacobian maps the internal robot shape with the relative velocity of refFrame w.r.t. frame expressed in the specified frame, i.e

\[ {}^{expressedOriginFrame, [expressedOrientationFrame]} \mathrm{v}_{refFrame, frame} = {}^{expressedOriginFrame, [expressedOrientationFrame]} J_{refFrame, frame}(s) \dot{s} \]

bool iDynTree::KinDynComputations::getRelativeJacobianExplicit(const iDynTree::FrameIndex refFrameIndex, const iDynTree::FrameIndex frameIndex, const iDynTree::FrameIndex expressedOriginFrameIndex, const iDynTree::FrameIndex expressedOrientationFrameIndex, iDynTree::MatrixView<double> outJacobian)

Return the relative Jacobian between the two frames (MatrixView implementation)

Parameters
refFrameIndex reference frame
frameIndex considered frame
expressedOriginFrameIndex frame whose origin is used to express the Jacobian
expressedOrientationFrameIndex frame whose orientation is used to express the Jacobian
outJacobian
Returns true on success, false otherwise.

The Jacobian maps the internal robot shape with the relative velocity of refFrame w.r.t. frame expressed in the specified frame, i.e

\[ {}^{expressedOriginFrame, [expressedOrientationFrame]} \mathrm{v}_{refFrame, frame} = {}^{expressedOriginFrame, [expressedOrientationFrame]} J_{refFrame, frame}(s) \dot{s} \]

Vector6 iDynTree::KinDynComputations::getFrameBiasAcc(const FrameIndex frameIdx)

Get the bias acceleration (i.e.

acceleration not due to robot acceleration) of the frame velocity.

This term is usually called $\dot{J} \nu$ or $\dot{J} \dot{q}$ .

bool iDynTree::KinDynComputations::getFrameBiasAcc(const FrameIndex frameIdx, iDynTree::Span<double> bias_acc)

Get the bias acceleration (i.e.

Returns true on success, false otherwise

acceleration not due to robot acceleration) of the frame velocity.

This term is usually called $\dot{J} \nu$ or $\dot{J} \dot{q}$ .

Vector6 iDynTree::KinDynComputations::getFrameBiasAcc(const std::string& frameName)

Get the bias acceleration (i.e.

acceleration not due to robot acceleration) of the frame velocity.

This term is usually called $\dot{J} \nu$ or $\dot{J} \dot{q}$ .

bool iDynTree::KinDynComputations::getFrameBiasAcc(const std::string& frameName, iDynTree::Span<double> bias_acc)

Get the bias acceleration (i.e.

Returns true on success, false otherwise

acceleration not due to robot acceleration) of the frame velocity.

This term is usually called $\dot{J} \nu$ or $\dot{J} \dot{q}$ .

iDynTree::Position iDynTree::KinDynComputations::getCenterOfMassPosition()

Return the center of mass position.

Returns the center of mass position, expressed in the world/inertial frame.

bool iDynTree::KinDynComputations::getCenterOfMassPosition(iDynTree::Span<double> pos)

Return the center of mass position.

Returns true on success, false otherwise.

iDynTree::Vector3 iDynTree::KinDynComputations::getCenterOfMassVelocity()

Return the center of mass velocity, with respect to the world/inertial frame.

bool iDynTree::KinDynComputations::getCenterOfMassVelocity(iDynTree::Span<double> vel)

Return the center of mass velocity, with respect to the world/inertial frame.

Returns true on success, false otherwise.

bool iDynTree::KinDynComputations::getCenterOfMassJacobian(MatrixDynSize& comJacobian)

Return the center of mass jacobian, i.e.

the $3 \times (n+6)$ matrix such that: getCenterOfMassVelocity() == getCenterOfMassJacobian() * $ \nu$ .

bool iDynTree::KinDynComputations::getCenterOfMassJacobian(iDynTree::MatrixView<double> comJacobian)

Return the center of mass jacobian, i.e.

Returns true on success, false otherwise.

the $3 \times (n+6)$ matrix such that: getCenterOfMassVelocity() == getCenterOfMassJacobian() * $\nu $ .

bool iDynTree::KinDynComputations::getCenterOfMassBiasAcc(iDynTree::Span<double> acc)

Return the center of mass bias acceleration.

Returns true on success, false otherwise.

iDynTree::Twist iDynTree::KinDynComputations::getAverageVelocity()

Get the average velocity of the robot.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getAverageVelocity(iDynTree::Span<double> acc)

Get the average velocity of the robot.

Returns true on success, false otherwise.

(Span implementation) The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getAverageVelocityJacobian(MatrixDynSize& avgVelocityJacobian)

Get the jacobian of the average velocity of the robot.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getAverageVelocityJacobian(iDynTree::MatrixView<double> avgVelocityJacobian)

Get the jacobian of the average velocity of the robot.

Returns true on success, false otherwise.

(MatrixView implementation) The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

SpatialInertia iDynTree::KinDynComputations::getRobotLockedInertia()

Get the robot locked inertia matrix.

Returns the locked inertia matrix of the robot.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

iDynTree::Twist iDynTree::KinDynComputations::getCentroidalAverageVelocity()

Get the centroidal average velocity of the robot.

The quantity is the average velocity returned by getAverageVelocity, but computed in the center of mass and with the orientation of the FrameVelocityRepresentation used. It we indicate with G the center of mass, it is expressed in (G[A]) for the mixed and inertial representation, and in (G[B]) for the base body-fixed representation.

bool iDynTree::KinDynComputations::getCentroidalAverageVelocity(iDynTree::Span<double> acc)

Get the centroidal average velocity of the robot (Span version).

Returns true on success, false otherwise.

The quantity is the average velocity returned by getAverageVelocity, but computed in the center of mass and with the orientation of the FrameVelocityRepresentation used. It we indicate with G the center of mass, it is expressed in (G[A]) for the mixed and inertial representation, and in (G[B]) for the base body-fixed representation.

bool iDynTree::KinDynComputations::getCentroidalAverageVelocityJacobian(MatrixDynSize& centroidalAvgVelocityJacobian)

Get the jacobian of the centroidal average velocity of the robot.

See the getCentroidalAverageVelocity method for more info on this.

bool iDynTree::KinDynComputations::getCentroidalAverageVelocityJacobian(iDynTree::MatrixView<double> centroidalAvgVelocityJacobian)

Get the jacobian of the centroidal average velocity of the robot (MatrixView version).

Returns true on success, false otherwise.

See the getCentroidalAverageVelocity method for more info on this.

SpatialInertia iDynTree::KinDynComputations::getCentroidalRobotLockedInertia()

Get the robot locked centroidal inertia matrix.

Returns the locked inertia centroidal matrix of the robot.

The quantity is expressed in (G[A]) or (G[B]) depending on the FrameVelocityConvention used.

iDynTree::SpatialMomentum iDynTree::KinDynComputations::getLinearAngularMomentum()

Get the linear and angular momentum of the robot.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getLinearAngularMomentum(iDynTree::Span<double> spatialMomentum)

Get the linear and angular momentum of the robot.

Returns true on success, false otherwise.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getLinearAngularMomentumJacobian(MatrixDynSize& linAngMomentumJacobian)

Get the linear and angular momentum jacobian of the robot.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getLinearAngularMomentumJacobian(iDynTree::MatrixView<double> linAngMomentumJacobian)

Get the linear and angular momentum jacobian of the robot (MatrixView implementation).

Returns true on success, false otherwise.

The quantity is expressed in (B[A]), (A) or (B) depending on the FrameVelocityConvention used.

iDynTree::SpatialMomentum iDynTree::KinDynComputations::getCentroidalTotalMomentum()

Get the centroidal (total) momentum of the robot.

If G is the center of mass, this quantity is expressed in (G[A]), (G[A]) or (G[B]) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getCentroidalTotalMomentum(iDynTree::Span<double> spatial_momentum)

Get the centroidal (total) momentum of the robot.

Returns true on success, false otherwise.

If G is the center of mass, this quantity is expressed in (G[A]), (G[A]) or (G[B]) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getCentroidalTotalMomentumJacobian(MatrixDynSize& centroidalTotalMomentumJacobian)

Get the total centroidal momentum jacobian of the robot.

Parameters
centroidalTotalMomentumJacobian out the (6) times (6+getNrOfDOFs()) output centroidal total momentum jacobian.
Returns true if all went well, false otherwise.

If G is the center of mass, this quantity is expressed in (G[A]), (G[A]) or (G[B]) depending on the FrameVelocityConvention used.

bool iDynTree::KinDynComputations::getCentroidalTotalMomentumJacobian(iDynTree::MatrixView<double> centroidalTotalMomentumJacobian)

Get the total centroidal momentum jacobian of the robot.

Parameters
centroidalTotalMomentumJacobian out the (6) times (6+getNrOfDOFs()) output centroidal total momentum jacobian.
Returns true if all went well, false otherwise.

If G is the center of mass, this quantity is expressed in (G[A]), (G[A]) or (G[B]) depending on the FrameVelocityConvention used (MatrixView implementation).

bool iDynTree::KinDynComputations::getFreeFloatingMassMatrix(MatrixDynSize& freeFloatingMassMatrix)

Get the free floating mass matrix of the system.

Parameters
freeFloatingMassMatrix out the (6+getNrOfDOFs()) times (6+getNrOfDOFs()) output mass matrix.
Returns true if all went well, false otherwise.

This method computes $M(q) \in \mathbb{R}^{(6+n_{DOF}) \times (6+n_{DOF})}$ .

The mass matrix depends on the joint positions, specified by the setRobotState methods. If the chosen FrameVelocityRepresentation is MIXED_REPRESENTATION or INERTIAL_FIXED_REPRESENTATION, the mass matrix depends also on the base orientation with respect to the inertial frame, that is also set by the setRobotState methods.

For more details on the structure of the free floating mass matrix, please check: S. Traversaro, A. Saccon Multibody Dynamics Notation http://repository.tue.nl/849895

bool iDynTree::KinDynComputations::getFreeFloatingMassMatrix(iDynTree::MatrixView<double> freeFloatingMassMatrix)

Get the free floating mass matrix of the system (MatrixView version).

Parameters
freeFloatingMassMatrix out the (6+getNrOfDOFs()) times (6+getNrOfDOFs()) output mass matrix.
Returns true if all went well, false otherwise.

This method computes $M(q) \in \mathbb{R}^{(6+n_{DOF}) \times (6+n_{DOF})}$ .

The mass matrix depends on the joint positions, specified by the setRobotState methods. If the chosen FrameVelocityRepresentation is MIXED_REPRESENTATION or INERTIAL_FIXED_REPRESENTATION, the mass matrix depends also on the base orientation with respect to the inertial frame, that is also set by the setRobotState methods.

For more details on the structure of the free floating mass matrix, please check: S. Traversaro, A. Saccon Multibody Dynamics Notation http://repository.tue.nl/849895

bool iDynTree::KinDynComputations::inverseDynamics(const Vector6& baseAcc, const VectorDynSize& s_ddot, const LinkNetExternalWrenches& linkExtForces, FreeFloatingGeneralizedTorques& baseForceAndJointTorques)

Compute the free floating inverse dynamics.

Parameters
baseAcc in the acceleration of the base link
s_ddot in the accelerations of the joints
linkExtForces in the external wrenches excerted by the environment on the model
baseForceAndJointTorques out the output generalized torques
Returns true if all went well, false otherwise

This method computes $M(q) \dot{\nu} + C(q, \nu) \nu + G(q) - \sum_{L \in \mathcal{L}} J_L^T \mathrm{f}_L^x \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of baseAcc, the base part of baseForceAndJointTorques and of the elements of linkExtWrenches depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::inverseDynamics(iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, const LinkNetExternalWrenches& linkExtForces, FreeFloatingGeneralizedTorques& baseForceAndJointTorques)

Compute the free floating inverse dynamics (Span version).

Parameters
baseAcc in the acceleration of the base link
s_ddot in the accelerations of the joints
linkExtForces in the external wrenches excerted by the environment on the model
baseForceAndJointTorques out the output generalized torques
Returns true if all went well, false otherwise.

This method computes $M(q) \dot{\nu} + C(q, \nu) \nu + G(q) - \sum_{L \in \mathcal{L}} J_L^T \mathrm{f}_L^x \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of baseAcc, the base part of baseForceAndJointTorques and of the elements of linkExtWrenches depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::inverseDynamicsWithInternalJointForceTorques(const Vector6& baseAcc, const VectorDynSize& s_ddot, const LinkNetExternalWrenches& linkExtForces, FreeFloatingGeneralizedTorques& baseForceAndJointTorques, LinkInternalWrenches& linkInternalWrenches)

This method is similar to inverseDynamics, but provides as an additional output the internal 6D force/torques (aka wrenches) excerted by the two links connected to each joint, in the linkInternalWrenches argument.

The linkInternalWrenches is a container of $n_{L}$ (number of links) 6D Force/Torques, one associated to each link. In particular, if the link $L$ is the link with index $L$ the element linkInternalWrenches(i) contains, depending on the choice of FrameVelocityRepresentation:

FrameVelocityRepresentationlinkInternalWrenches(i)
MIXED_REPRESENTATION (default) $ {}_{L[A]} \mathrm{f}_{\lambda(L), L} $
BODY_FIXED_REPRESENTATION $ {}_{L} \mathrm{f}_{\lambda(L), L} $
INERTIAL_FIXED_REPRESENTATION $ {}_{A} \mathrm{f}_{\lambda(L), L} $

Where if $C$ is a given frame, $ {}_{C} \mathrm{f}_{\lambda(L), L} $ is the 6D force/torque that the parent link $\lambda(L)$ excerts on its child $L$ expressed in frame $C$ .

bool iDynTree::KinDynComputations::inverseDynamicsWithInternalJointForceTorques(iDynTree::Span<const double> baseAcc, iDynTree::Span<const double> s_ddot, const LinkNetExternalWrenches& linkExtForces, FreeFloatingGeneralizedTorques& baseForceAndJointTorques, LinkInternalWrenches& linkInternalWrenches)

Variant of inverseDynamicsWithInternalJointForceTorques that takes iDynTree::Span objects that point to already allocated memory as inputs.

See inverseDynamicsWithInternalJointForceTorques for the description of the input and output parameters.

bool iDynTree::KinDynComputations::generalizedBiasForces(FreeFloatingGeneralizedTorques& generalizedBiasForces)

Compute the getNrOfDOFS()+6 vector of generalized bias (gravity+coriolis) forces.

Parameters
generalizedBiasForces out the output generalized bias forces
Returns true if all went well, false otherwise

This method computes $C(q, \nu) \nu + G(q) \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of the base part of generalizedBiasForces depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::generalizedBiasForces(iDynTree::Span<double> generalizedBiasForces)

Compute the getNrOfDOFS()+6 vector of generalized bias (gravity+coriolis) forces.

Returns true if all went well, false otherwise.

(Span version)

This method computes $C(q, \nu) \nu + G(q) \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of the base part of generalizedBiasForces depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::generalizedGravityForces(FreeFloatingGeneralizedTorques& generalizedGravityForces)

Compute the getNrOfDOFS()+6 vector of generalized gravity forces.

Parameters
generalizedGravityForces out the output gravity generalized forces
Returns true if all went well, false otherwise

This method computes $G(q) \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of the base part of generalizedGravityForces depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::generalizedGravityForces(iDynTree::Span<double> generalizedGravityForces)

Compute the getNrOfDOFS()+6 vector of generalized gravity forces.

Returns true if all went well, false otherwise.

This method computes $G(q) \in \mathbb{R}^{6+n_{DOF}}$ .

The semantics of the base part of generalizedGravityForces depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::generalizedExternalForces(const LinkNetExternalWrenches& linkExtForces, FreeFloatingGeneralizedTorques& generalizedExternalForces)

Compute the getNrOfDOFS()+6 vector of generalized external forces.

Parameters
linkExtForces
generalizedExternalForces out the output external generalized forces
Returns true if all went well, false otherwise

This method computes $ -\sum_{L \in \mathcal{L}} J_L^T \mathrm{f}_L^x \in \mathbb{R}^{6+n_{DOF}} $ .

The semantics of the base part of generalizedExternalForces and of the elements of linkExtWrenches depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.

bool iDynTree::KinDynComputations::inverseDynamicsInertialParametersRegressor(const Vector6& baseAcc, const VectorDynSize& s_ddot, MatrixDynSize& baseForceAndJointTorquesRegressor)

Compute the free floating inverse dynamics as a linear function of inertial parameters.

Parameters
baseAcc in the acceleration of the base link
s_ddot in the accelerations of the joints
baseForceAndJointTorquesRegressor out The (6+model.getNrOfDOFs() X 10*model.getNrOfLinks()) inverse dynamics regressor.
Returns true if all went well, false otherwise

This methods computes the $ Y(\dot{\nu}, \nu, q) \in \mathbb{R}^{ (6+n_{DOF}) \times (10n_{L}) } $ matrix such that:

\[ Y(\dot{\nu}, \nu, q) \phi = M(q) \dot{\nu} + C(q, \nu) \nu + G(q) \]

where $\phi \in \mathbb{R}^{10n_{L}}$ is the vector of inertial parameters returned by the Model::getInertialParameters .

The semantics of baseAcc, the base part (first six rows) of baseForceAndJointTorquesRegressor depend of the chosen FrameVelocityRepresentation .

The state is the one given set by the setRobotState method.