Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update Matlab high-level wrappers #1199

Merged
merged 4 commits into from
Aug 5, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions bindings/matlab/+iDynTreeWrappers/README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# idyntree high-level-wrappers
# iDynTree high-level-wrappers

A collection of Matlab/Octave functions that wraps the functionalities of (mainly) the iDyntree class `KinDynComputations`. For further information on the single wrapper, refer to the description included in each function.

Expand Down Expand Up @@ -74,16 +74,20 @@ The purpose of the wrapper is therefore to provide a simpler and easy-to-use int

Not proper wrappers, they wrap more than one method of the class each. **Requirements:** compile iDyntree with Irrlicht `(IDYNTREE_USES_IRRLICHT = ON)`.

**Warning**: the visualizer class may be deprecated in a future release.

- [initializeVisualizer](initializeVisualizer.m)
- [visualizerSetup](visualizerSetup.m)
- [updateVisualizer](updateVisualizer.m)

## Matlab Native visualization

Not actual wrappers, they use the iDynTreeWrappers in combination with the MATLAB patch plotting functions to visualize the robot.

**Disclaimers**:
- This visualization **has not been tested** with Octave.
- At the moment, there is **no support** for .dae mesh files.

1) This visualization **has not been tested** with Octave.
2) At the moment, there is **no support** for `.dae` mesh file format.

- [prepareVisualization](prepareVisualization.m)
- [updateVisualization](updateVisualization.m)
Expand Down
23 changes: 10 additions & 13 deletions bindings/matlab/+iDynTreeWrappers/generalizedBiasForces.m
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
function h = generalizedBiasForces(KinDynModel)

% GENERALIZEDBIASFORCES retrieves the generalized bias forces from
% the reduced model.
% GENERALIZEDBIASFORCES retrieves the generalized bias forces from
% the reduced model.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: h = generalizedBiasForces(KinDynModel)
Expand All @@ -15,24 +15,21 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% create the vector that must be populated with the bias forces
h_iDyntree = iDynTree.FreeFloatingGeneralizedTorques(KinDynModel.kinDynComp.model);


% get the bias forces
ack = KinDynModel.kinDynComp.generalizedBiasForces(h_iDyntree);
ack = KinDynModel.kinDynComp.generalizedBiasForces(KinDynModel.dynamics.h_iDyntree);

% check for errors
if ~ack
error('[generalizedBiasForces]: unable to get the bias forces from the reduced model.')
end

% convert to Matlab format: compute the base bias acc (h_b) and the
% joint bias acc (h_s) and concatenate them
h_b = h_iDyntree.baseWrench.toMatlab;
h_s = h_iDyntree.jointTorques.toMatlab;
h_b = KinDynModel.dynamics.h_iDyntree.baseWrench.toMatlab;
h_s = KinDynModel.dynamics.h_iDyntree.jointTorques.toMatlab;
h = [h_b;h_s];
end
25 changes: 11 additions & 14 deletions bindings/matlab/+iDynTreeWrappers/generalizedGravityForces.m
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
function g = generalizedGravityForces(KinDynModel)

% GENERALIZEDGRAVITYFORCES retrieves the generalized gravity forces
% given the reduced model.
% GENERALIZEDGRAVITYFORCES retrieves the generalized gravity forces
% given the reduced model.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: g = generalizedGravityForces(KinDynModel)
Expand All @@ -15,24 +15,21 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% create the vector that must be populated with the gravity forces
g_iDyntree = iDynTree.FreeFloatingGeneralizedTorques(KinDynModel.kinDynComp.model);


% get the gravity forces
ack = KinDynModel.kinDynComp.generalizedGravityForces(g_iDyntree);
ack = KinDynModel.kinDynComp.generalizedGravityForces(KinDynModel.dynamics.g_iDyntree);

% check for errors
if ~ack
if ~ack
error('[generalizedGravityForces]: unable to get the gravity forces from the reduced model.')
end

% convert to Matlab format: compute the base gravity forces (g_b) and the
% joint gravity forces (g_j) and concatenate them
g_b = g_iDyntree.baseWrench.toMatlab;
g_s = g_iDyntree.jointTorques.toMatlab;
g_b = KinDynModel.dynamics.g_iDyntree.baseWrench.toMatlab;
g_s = KinDynModel.dynamics.g_iDyntree.jointTorques.toMatlab;
g = [g_b; g_s];
end
6 changes: 3 additions & 3 deletions bindings/matlab/+iDynTreeWrappers/getBaseTwist.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

% GETBASETWIST retrieves the robot base velocity from the reduced model.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: baseVel = getBaseTwist(KinDynModel)
Expand All @@ -14,13 +14,13 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% get the base velocities
baseVel_iDyntree = KinDynModel.kinDynComp.getBaseTwist();

% convert to Matlab format
baseVel = baseVel_iDyntree.toMatlab;
end
19 changes: 8 additions & 11 deletions bindings/matlab/+iDynTreeWrappers/getCenterOfMassJacobian.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

% GETCENTEROFMASSJACOBIAN retrieves the CoM jacobian.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: J_CoM = getCenterOfMassJacobian(KinDynModel)
Expand All @@ -14,21 +14,18 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% create the matrix that must be populated with the jacobian map
J_CoM_iDyntree = iDynTree.MatrixDynSize(3,KinDynModel.NDOF+6);


% get the free floating jacobian
ack = KinDynModel.kinDynComp.getCenterOfMassJacobian(J_CoM_iDyntree);
ack = KinDynModel.kinDynComp.getCenterOfMassJacobian(KinDynModel.kinematics.J_CoM_iDyntree);

% check for errors
if ~ack
if ~ack
error('[getCenterOfMassJacobian]: unable to get the CoM Jacobian from the reduced model.')
end

% convert to Matlab format
J_CoM = J_CoM_iDyntree.toMatlab;
J_CoM = KinDynModel.kinematics.J_CoM_iDyntree.toMatlab;
end
10 changes: 5 additions & 5 deletions bindings/matlab/+iDynTreeWrappers/getCenterOfMassPosition.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

% GETCENTEROFMASSPOSITION retrieves the CoM position in world coordinates.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: posCoM = getCenterOfMassPosition(KinDynModel)
Expand All @@ -14,13 +14,13 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% get the CoM position
posCoM_iDyntree = KinDynModel.kinDynComp.getCenterOfMassPosition();
posCoM_iDyntree = KinDynModel.kinDynComp.getCenterOfMassPosition();

% covert to matlab
posCoM = posCoM_iDyntree.toMatlab;
end
12 changes: 6 additions & 6 deletions bindings/matlab/+iDynTreeWrappers/getCenterOfMassVelocity.m
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

% GETCENTEROFMASSVELOCITY retrieves the CoM velocity in world coordinates.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: velCoM = getCenterOfMassVelocity(KinDynModel)
Expand All @@ -14,13 +14,13 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

%% ------------Initialization----------------

% get the CoM velocity
velCoM_iDyntree = KinDynModel.kinDynComp.getCenterOfMassVelocity();
velCoM_iDyntree = KinDynModel.kinDynComp.getCenterOfMassVelocity();

% covert to matlab
velCoM = velCoM_iDyntree.toMatlab;
end
12 changes: 6 additions & 6 deletions bindings/matlab/+iDynTreeWrappers/getCentroidalTotalMomentum.m
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
function totalMomentum = getCentroidalTotalMomentum(KinDynModel)

% GETCENTROIDALTOTALMOMENTUM retrieves the centroidal momentum from the reduced
% model. The quantity is expressed in a frame that depends
% on the 'FrameVelocityReperesentation' settings.
% model. The quantity is expressed in a frame that depends
% on the 'FrameVelocityReperesentation' settings.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: totalMomentum = getCentroidalTotalMomentum(KinDynModel)
Expand All @@ -16,13 +16,13 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% get the momentum
totalMomentum_iDyntree = KinDynModel.kinDynComp.getCentroidalTotalMomentum();

% convert to Matlab format
totalMomentum = totalMomentum_iDyntree.toMatlab;
end
12 changes: 6 additions & 6 deletions bindings/matlab/+iDynTreeWrappers/getFloatingBase.m
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
function baseLinkName = getFloatingBase(KinDynModel)

% GETFLOATINGBASE retrieves the floating base link name from the
% reduced model.
% GETFLOATINGBASE retrieves the floating base link name from the
% reduced model.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: baseLinkName = getFloatingBase(KinDynModel)
Expand All @@ -15,10 +15,10 @@
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% get the name of the floating base link
baseLinkName = KinDynModel.kinDynComp.getFloatingBase();
baseLinkName = KinDynModel.kinDynComp.getFloatingBase();
end
14 changes: 7 additions & 7 deletions bindings/matlab/+iDynTreeWrappers/getFrameBiasAcc.m
Original file line number Diff line number Diff line change
@@ -1,28 +1,28 @@
function JDot_nu_frame = getFrameBiasAcc(KinDynModel,frameName)

% GETFRAMEBIASACC gets the bias accelerations of a specified frame.
% GETFRAMEBIASACC gets the bias accelerations of a specified frame.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: JDot_nu_frame = getFrameBiasAcc(KinDynModel,frameName)
%
% INPUTS: - KinDynModel: a structure containing the loaded model and additional info.
% - frameName: a string that specifies the frame w.r.t. compute the
% bias accelerations, or the associated ID;
% - frameName: a string that specifies the frame w.r.t. compute the
% bias accelerations, or the associated ID;
%
% OUTPUTS: - JDot_nu_frame: [6 x 6+ndof] frame bias accelerations.
%
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% get the bias acc
JDot_nu_frame_iDyntree = KinDynModel.kinDynComp.getFrameBiasAcc(frameName);

% convert to Matlab format
JDot_nu_frame = JDot_nu_frame_iDyntree.toMatlab;
end
27 changes: 12 additions & 15 deletions bindings/matlab/+iDynTreeWrappers/getFrameFreeFloatingJacobian.m
Original file line number Diff line number Diff line change
@@ -1,37 +1,34 @@
function J_frame = getFrameFreeFloatingJacobian(KinDynModel,frameName)

% GETFRAMEFREEFLOATINGJACOBIAN gets the free floating jacobian of a
% specified frame.
% GETFRAMEFREEFLOATINGJACOBIAN gets the free floating jacobian of a
% specified frame.
%
% This matlab function wraps a functionality of the iDyntree library.
% This matlab function wraps a functionality of the iDyntree library.
% For further info see also: https://github.com/robotology/idyntree
%
% FORMAT: J_frame = getFrameFreeFloatingJacobian(KinDynModel,frameName)
%
% INPUTS: - KinDynModel: a structure containing the loaded model and additional info.
% - frameName: a string that specifies the frame w.r.t. compute the
% jacobian matrix, or the associated ID;
% - frameName: a string that specifies the frame w.r.t. compute the
% jacobian matrix, or the associated ID;
%
% OUTPUTS: - J_frame: [6 x 6+ndof] frame free floating Jacobian.
%
% Author : Gabriele Nava ([email protected])
%
% SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
% SPDX-License-Identifier: BSD-3-Clause
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------

% create the matrix that must be populated with the jacobian map
J_frame_iDyntree = iDynTree.MatrixDynSize(6,KinDynModel.NDOF+6);


% get the free floating jacobian
ack = KinDynModel.kinDynComp.getFrameFreeFloatingJacobian(frameName,J_frame_iDyntree);
ack = KinDynModel.kinDynComp.getFrameFreeFloatingJacobian(frameName,KinDynModel.kinematics.J_frame_iDyntree);

% check for errors
if ~ack
if ~ack
error('[getFrameFreeFloatingJacobian]: unable to get the Jacobian from the reduced model.')
end

% convert to Matlab format
J_frame = J_frame_iDyntree.toMatlab;
J_frame = KinDynModel.kinematics.J_frame_iDyntree.toMatlab;
end
Loading
Loading