Skip to content

Commit

Permalink
Merge pull request #1126 from LoreMoretti/improve/loadReducedModel
Browse files Browse the repository at this point in the history
Update loadReducedModel.m to use fullfile Matlab function
  • Loading branch information
traversaro authored Nov 21, 2023
2 parents f4df648 + c72ab02 commit 96b17da
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 3 deletions.
3 changes: 3 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ The following errors are currently check:
### Changed
- No warning is printed if a sensor not supported by iDynTree is found in an URDF file (https://github.com/robotology/idyntree/pull/997).

### Fixed
- Fix `iDynTreeWrappers.loadReducedModel` when `model_path` argument does not end in `\` (https://github.com/robotology/idyntree/pull/1126).

## [5.2.1] - 2022-05-19

### Fixed
Expand Down
6 changes: 3 additions & 3 deletions bindings/matlab/+iDynTreeWrappers/loadReducedModel.m
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
% SPDX-License-Identifier: BSD-3-Clause

%% ------------Initialization----------------
disp(['[loadReducedModel]: loading the following model: ',[modelPath,modelName]]);
disp(['[loadReducedModel]: loading the following model: ',fullfile(modelPath,modelName)]);

% if DEBUG option is set to TRUE, all the wrappers will be run in debug
% mode. Wrappers concerning iDyntree simulator have their own debugger
Expand All @@ -44,7 +44,7 @@
modelLoader = iDynTree.ModelLoader();
reducedModel = modelLoader.model();

modelLoader.loadReducedModelFromFile([modelPath,modelName], jointList_idyntree);
modelLoader.loadReducedModelFromFile(fullfile(modelPath,modelName), jointList_idyntree);

% get the number of degrees of freedom of the reduced model
KinDynModel.NDOF = reducedModel.getNrOfDOFs();
Expand All @@ -58,5 +58,5 @@
% set the floating base link
KinDynModel.kinDynComp.setFloatingBase(KinDynModel.BASE_LINK);

disp(['[loadReducedModel]: loaded model: ',[modelPath,modelName],', number of joints: ',num2str(KinDynModel.NDOF)]);
disp(['[loadReducedModel]: loaded model: ',fullfile(modelPath,modelName),', number of joints: ',num2str(KinDynModel.NDOF)]);
end

0 comments on commit 96b17da

Please sign in to comment.