Skip to content
This repository has been archived by the owner on Sep 29, 2020. It is now read-only.

Commit

Permalink
fixed (hopefully all) bugs from smartIndent and startup.m
Browse files Browse the repository at this point in the history
  • Loading branch information
gabrielenava committed Aug 4, 2016
1 parent ffcdb98 commit 960166e
Show file tree
Hide file tree
Showing 34 changed files with 223 additions and 247 deletions.
6 changes: 3 additions & 3 deletions startup_Mex.m.in → .startup_mexWholeBodyModel.m.in
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
%% startup_Mex.m
%% startup_mexWholeBodyModel.m
% Run this script only once to permanently add the required folders for using mexWholebodymodel toolbox to your
% MATLAB path.

fprintf('\nmexWholeBodyModel Toolbox\n');

installDir = '@CMAKE_BINARY_DIR@/install';
installDir = '@CMAKE_INSTALL_PREFIX@';
mexDir = [installDir, filesep, 'mex'];
mexWrapDir = [mexDir, filesep, 'mexwbi-wrappers'];
mexUtDir = [mexDir, filesep, 'mexwbi-utilities'];
Expand Down Expand Up @@ -38,7 +38,7 @@ fprintf('Saving paths to %s\n\n', [fileDir, filesep, 'pathdef.m']);

if (~savepath([fileDir, filesep, 'pathdef.m']))
fprintf(['A file called pathdef.m has been created in your %s folder.\n', ...
'This should be enough to permanentely add all the Mex-Toolbox to ', ...
'This should be enough to permanentely add all the mexWholeBodyModel-Toolbox to ', ...
'your MATLAB installation.\n'], fileDir);
else
disp('There was an error generating pathdef.m To proceed please manually add the contents of variables mexDir, mexUtDir, mexWrapDir to your matlabpath');
Expand Down
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,11 +59,11 @@ enable_testing()

add_subdirectory(tests)

#STARTUP MEX-TOOLBOX
# The following line is to properly configure the installation script of the Mex-toolbox
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/startup_Mex.m.in ${CMAKE_BINARY_DIR}/startup_Mex.m)
#STARTUP mexWholeBodyModel-TOOLBOX
# The following line is to properly configure the installation script of the mexWholeBodyModel-toolbox
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/.startup_mexWholeBodyModel.m.in ${CMAKE_BINARY_DIR}/startup_mexWholeBodyModel.m)
# Install configuration files
install(FILES ${CMAKE_BINARY_DIR}/startup_Mex.m DESTINATION ${CMAKE_INSTALL_PREFIX}/mex)
install(FILES ${CMAKE_BINARY_DIR}/startup_mexWholeBodyModel.m DESTINATION mex)



4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ Matlab MEX interface to the wholeBodyModel C++ interface, implemented to be able
It is recommended to install the `mex-wholebodymodel` throught the [`codyco-superbuild`](https://github.com/robotology/codyco-superbuild/).
Once you installed the `codyco-superbuild`, the `mex-wholebodymodel` files should have been installed in
`${CODYCO_SUPERBUILD_ROOT}/build/install/mex` and its subdirectories (for the `mex-wholebodymodel`, this directories are `mexwbi-wrappers` and `mexwbi-utilities`).
To execute scripts that use `mex-wholebodymodel`, make sure that this directories are part of your [MATLAB search path](http://www.mathworks.com/help/matlab/ref/path.html). To this purpose, run only once the script `startupMex.m` in
`${CODYCO_SUPERBUILD_ROOT}/main/mexWholeBodyModel`. This should be enough to premanently add the required directories to your MATLAB path.
To execute scripts that use `mex-wholebodymodel`, make sure that this directories are part of your [MATLAB search path](http://www.mathworks.com/help/matlab/ref/path.html). To this purpose, run only once the script `startup_mexWholeBodyModel.m` in
`${CODYCO_SUPERBUILD_ROOT}/build/install/mex`. This should be enough to premanently add the required directories to your MATLAB path.

## Examples

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,19 +57,19 @@
% run the simulation with CONFIG.linearizationDebug = 1 to verify that the
% joint space linearization is performed properly, and to check the
% controlled system's stability
CONFIG.linearizationDebug = 1; %either 0 or 1
CONFIG.linearizationDebug = 1; %either 0 or 1

% enter in debug mode
if CONFIG.linearizationDebug == 1

CONFIG.demo_movements = 0;
CONFIG.use_QPsolver = 0;
CONFIG.demo_movements = 0;
CONFIG.use_QPsolver = 0;
end

%% Forward dynamics integration setup
% CONFIG.integrateWithFixedStep will use a Euler forward integrator instead
% of ODE15s to integrate the forward dynamics.
CONFIG.integrateWithFixedStep = 0; %either 0 or 1
CONFIG.integrateWithFixedStep = 0; %either 0 or 1

% The fixed step integration needs a desingularization of system mass matrix
% to converge to a solution
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@
if CONFIG.linearizationDebug == 1
% linearized joint accelerations
visualization.ddqjLin = trajectory.JointReferences.ddqjRef-CONFIG.linearization.KS*(qj-trajectory.JointReferences.qjRef)...
-CONFIG.linearization.KD*(dqj-trajectory.JointReferences.dqjRef);
-CONFIG.linearization.KD*(dqj-trajectory.JointReferences.dqjRef);
end

%% Balancing controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
use_QPsolver = CONFIG.use_QPsolver;
initForKinematics = CONFIG.initForKinematics;
S = [zeros(6,ndof);
eye(ndof,ndof)];
eye(ndof,ndof)];

%% Dynamics
dJcNu = DYNAMICS.dJcNu;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,20 +72,20 @@
% General parameters
gravAcc = 9.81;
S = [zeros(6,ndof);
eye(ndof,ndof)];
eye(ndof,ndof)];
f_grav = [zeros(2,1);
-m*gravAcc;
zeros(3,1)];
-m*gravAcc;
zeros(3,1)];

%% Multiplier of contact wrenches at CoM
posRFoot = RFootPoseEul(1:3);
posLFoot = LFootPoseEul(1:3);
distRF = posRFoot - xCoM; % Application point of the contact force on the right foot w.r.t. CoM
distLF = posLFoot - xCoM; % Application point of the contact force on the left foot w.r.t. CoM
AL = [eye(3), zeros(3);
skew(distLF),eye(3)];
skew(distLF),eye(3)];
AR = [eye(3), zeros(3);
skew(distRF),eye(3)];
skew(distRF),eye(3)];

% One foot or two feet on ground selector
if sum(feet_on_ground) == 2
Expand Down Expand Up @@ -132,7 +132,7 @@
posturalCorr = CONFIG.linearization.BNull;

tauModel = pinvLambda*(JcMinv*h - dJcNu) + NullLambda*(h(7:end) -Mbj'/Mb*h(1:6)...
+ Mbar*ddqjRef - impedances*posturalCorr*qjTilde - dampings*posturalCorr*dqjTilde);
+ Mbar*ddqjRef - impedances*posturalCorr*qjTilde - dampings*posturalCorr*dqjTilde);

%% Desired contact forces computation
fcHDot = pinvA*(HDotDes - f_grav);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
% Initial parameters
directionOfOscillation = [0;0;0];
referenceParams = [0.0 0.0]; %referenceParams(1) = amplitude of ascillations in meters
%referenceParams(2) = frequency of ascillations in Hertz
%referenceParams(2) = frequency of ascillations in Hertz

noOscillationTime = 0; % If params.demo_movements = 1, the variable noOscillationTime is the time, in seconds,
% that the robot waits before starting the left-and-right
% that the robot waits before starting the left-and-right

%% Trajectory definition
if demo_movements == 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
feet_on_ground = CONFIG.feet_on_ground;
initForKinematics = CONFIG.initForKinematics;
S = [zeros(6,ndof);
eye(ndof,ndof)];
eye(ndof,ndof)];

%% Dynamics
dJcNu = DYNAMICS.dJcNu;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,10 +21,10 @@
% Initial parameters
directionOfOscillation = [0;0;0];
referenceParams = [0.0 0.0]; %referenceParams(1) = amplitude of ascillations in meters
%referenceParams(2) = frequency of ascillations in Hertz
%referenceParams(2) = frequency of ascillations in Hertz

noOscillationTime = 0; % If params.demo_movements = 1, the variable noOscillationTime is the time, in seconds,
% that the robot waits before starting the left-and-right
% that the robot waits before starting the left-and-right

%% Trajectory definition
if demo_movements == 1
Expand Down
Loading

0 comments on commit 960166e

Please sign in to comment.