diff --git a/README.md b/README.md
index 3b898ec892de121a94d9e2e2003c0a689f96bbdc..e794dbc26aef51dafd016571736a82d97652d555 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,7 @@
 # pbdlib-matlab
 
-PbDLib is a set of tools combining statistical learning, dynamical systems and optimal control approaches for programming-by-demonstration applications. The Matlab/GNU Octave version is currently maintained by Sylvain Calinon, Idiap Research Institute, http://idiap.ch/~scalinon/, http://calinon.ch.
+PbDlib is a set of tools combining statistical learning, dynamical systems and optimal control approaches for programming-by-demonstration applications, http://www.idiap.ch/software/pbdlib/. 
+The Matlab/GNU Octave version is currently maintained by Sylvain Calinon, Idiap Research Institute.
 
 A C++ version of the library (with currently fewer functionalities) is available at https://gitlab.idiap.ch/rli/pbdlib
 
@@ -14,7 +15,7 @@ Examples starting with `demo_` can be run from Matlab/GNU Octave.
 
 ### References
 
-Did you find PbDLib useful for your research? Please acknowledge the authors in any academic publications that used some parts of these codes.
+Did you find PbDLib useful for your research? Please acknowledge the authors in any academic publications that used parts of these codes.
 
 ```
 @article{Calinon15,
@@ -39,6 +40,23 @@ Did you find PbDLib useful for your research? Please acknowledge the authors in
 
 The folder "data" contains a dataset of 2D handwriting movements from LASA-EPFL (http://lasa.epfl.ch), collected within the context of the AMARSI European Project. Reference: S.M. Khansari-Zadeh and A. Billard, "Learning Stable Non-Linear Dynamical Systems with Gaussian Mixture Models", IEEE Transaction on Robotics, 2011.
 
+### License
+
+Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+Written by Sylvain Calinon, http://calinon.ch/
+
+PbDlib is free software: you can redistribute it and/or modify
+it under the terms of the GNU General Public License version 3 as
+published by the Free Software Foundation.
+
+PbDlib is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+GNU General Public License for more details.
+
+You should have received a copy of the GNU General Public License
+along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
+
 ### List of examples
 
 All the examples are located in the main folder, and the functions are located in the `m_fcts` folder.
diff --git a/benchmark_DS_GP_GMM01.m b/benchmark_DS_GP_GMM01.m
index 5cef271592bbdc620ee63da384064115b440749e..786907d5dec8da34aae20e3712ae38f28ab5662b 100644
--- a/benchmark_DS_GP_GMM01.m
+++ b/benchmark_DS_GP_GMM01.m
@@ -1,18 +1,36 @@
 function benchmark_DS_GP_GMM01
 % Benchmark of task-parameterized model based on Gaussian process regression, 
-% with trajectory model (Gaussian mixture model encoding), and DS-GMR used for reproduction
+% with trajectory model (Gaussian mixture model encoding), and DS-GMR used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
+
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_GP_raw01.m b/benchmark_DS_GP_raw01.m
index 32d2966949bad4eca4b44d731b102ddc025fe083..cb4f4cbe6da54334e73285a4768bf8cc31c9efac 100644
--- a/benchmark_DS_GP_raw01.m
+++ b/benchmark_DS_GP_raw01.m
@@ -1,18 +1,35 @@
 function benchmark_DS_GP_raw01
 % Benchmark of task-parameterized model based on Gaussian process regression, 
-% with raw trajectory, and spring-damper system used for reproduction
+% with raw trajectory, and spring-damper system used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_PGMM01.m b/benchmark_DS_PGMM01.m
index d33b277eeb98c42c3bd94fcaf696829e6816d8ca..8a9a46948d98020949da237a9a9137d2cbb88ddc 100644
--- a/benchmark_DS_PGMM01.m
+++ b/benchmark_DS_PGMM01.m
@@ -1,17 +1,35 @@
 function benchmark_DS_PGMM01
-% Benchmark of task-parameterized model based on parametric Gaussian mixture model, and DS-GMR used for reproduction
+% Benchmark of task-parameterized model based on parametric Gaussianvmixture model, 
+% and DS-GMR used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_TP_GMM01.m b/benchmark_DS_TP_GMM01.m
index 5a0dc70cbffc41b802ea58d5b82ab695b84220ed..9a703cff876e8a02197a4f7009b3f4c59bce0f8c 100644
--- a/benchmark_DS_TP_GMM01.m
+++ b/benchmark_DS_TP_GMM01.m
@@ -1,17 +1,35 @@
 function benchmark_DS_TP_GMM01
-% Benchmark of task-parameterized Gaussian mixture model (TP-GMM), with DS-GMR used for reproduction
+% Benchmark of task-parameterized Gaussian mixture model (TP-GMM), 
+% with DS-GMR used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_TP_GP01.m b/benchmark_DS_TP_GP01.m
index dfc4fe7058342bb2226f6078161d9e91a6b970ee..72e2e906a2e56de6ea1a94661b5f74564744c44e 100644
--- a/benchmark_DS_TP_GP01.m
+++ b/benchmark_DS_TP_GP01.m
@@ -1,17 +1,34 @@
 function benchmark_DS_TP_GP01
-% Benchmark of task-parameterized Gaussian process (nonparametric task-parameterized method)
+% Benchmark of task-parameterized Gaussian process (nonparametric task-parameterized method).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_TP_LWR01.m b/benchmark_DS_TP_LWR01.m
index a6cf26cb59fb344066dc288dda46b3d598e162d2..c536db449b74be77cfa8fec915b245dd7c08ff04 100644
--- a/benchmark_DS_TP_LWR01.m
+++ b/benchmark_DS_TP_LWR01.m
@@ -1,17 +1,34 @@
 function benchmark_DS_TP_LWR01
-% Benchmark of task-parameterized locally weighted regression (nonparametric task-parameterized method)
+% Benchmark of task-parameterized locally weighted regression (nonparametric task-parameterized method).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_TP_MFA01.m b/benchmark_DS_TP_MFA01.m
index 1f06468d68165ff459761124440646ff7c0dc3df..cfde9fbf6a00859f3cd6504d5081c146bfa445cb 100644
--- a/benchmark_DS_TP_MFA01.m
+++ b/benchmark_DS_TP_MFA01.m
@@ -1,17 +1,35 @@
 function benchmark_DS_TP_MFA01
-% Benchmark of task-parameterized mixture of factor analyzers (TP-MFA), with DS-GMR used for reproduction
+% Benchmark of task-parameterized mixture of factor analyzers (TP-MFA), 
+% with DS-GMR used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/benchmark_DS_TP_trajGMM01.m b/benchmark_DS_TP_trajGMM01.m
index 84053ddd25f5f1b3fbcc07d63f22c19995956412..c4273db110676e586481e2c44e9b9d1a6a92ea0f 100644
--- a/benchmark_DS_TP_trajGMM01.m
+++ b/benchmark_DS_TP_trajGMM01.m
@@ -1,17 +1,35 @@
 function benchmark_DS_TP_trajGMM01
-% Benchmark of task-parameterized Gaussian mixture model (TP-GMM), with DS used for reproduction
+% Benchmark of task-parameterized Gaussian mixture model (TP-GMM), 
+% with dynamical system used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demoIK_nullspace_TPGMM01.m b/demoIK_nullspace_TPGMM01.m
index 380d98972d5a4b88c9394176ddc405f1327551fd..f144c8e7e5ceac61675e7091b918c4d6ed33c8b8 100644
--- a/demoIK_nullspace_TPGMM01.m
+++ b/demoIK_nullspace_TPGMM01.m
@@ -1,19 +1,38 @@
 function demoIK_nullspace_TPGMM01
 % Inverse kinematics with nullspace treated with task-parameterized GMM (bimanual tracking task, version with 4 frames).
-%
 % This example requires Peter Corke's robotics toolbox (run 'startup_rvc' from the robotics toolbox).
 %
 % Sylvain Calinon, 2015
 % http://programming-by-demonstration.org/lib/
 %
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demoIK_pointing_TPGMM01.m b/demoIK_pointing_TPGMM01.m
index cbf56d00163b6300754d5e25d2718b903dcf2164..b6c7dc6825edf6447c6254041980076633cd70d5 100644
--- a/demoIK_pointing_TPGMM01.m
+++ b/demoIK_pointing_TPGMM01.m
@@ -1,21 +1,37 @@
 function demoIK_pointing_TPGMM01
 % Task-parameterized GMM to encode pointing direction by considering nullspace constraint (4 frames) 
 % (example with two objects and robot frame, starting from the same initial pose (nullspace constraint), 
-% by using a single Euler orientation angle and 3 DOFs robot)
-%
+% by using a single Euler orientation angle and 3 DOFs robot).
 % This example requires Peter Corke's Robotics Toolbox (run 'startup_rvc' from the Robotics Toolbox).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_DMP_GMR01.m b/demo_DMP_GMR01.m
index 562b599c4878aed33b469d747b579b5abbce5637..99cd18ff34ce6f7a118b2c3274c552ef42d4cc61 100644
--- a/demo_DMP_GMR01.m
+++ b/demo_DMP_GMR01.m
@@ -1,10 +1,39 @@
 function demo_DMP_GMR01
-%Emulation of a standard dynamic movement primitive (DMP) model by using a Gaussian mixture model (GMM) 
-%with diagonal convariance matrix, and retrieval computed through Gaussian mixture regression (GMR) 
-%Sylvain Calinon, 2015
+% Emulation of a standard dynamic movement primitive (DMP) model by using a Gaussian mixture model (GMM) 
+% with diagonal covariance matrix, and retrieval computed through Gaussian mixture regression (GMR). 
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 5; %Number of activation functions (i.e., number of states in the GMM)
diff --git a/demo_DMP_GMR02.m b/demo_DMP_GMR02.m
index 1721e7475b249183eb7a5d90ab0cf6ace65d4466..2f17affe5f8f7e8c7f4fa57784961ac351376e96 100644
--- a/demo_DMP_GMR02.m
+++ b/demo_DMP_GMR02.m
@@ -1,11 +1,41 @@
 function demo_DMP_GMR02
-%Example of enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture model (GMM) representation, 
-%with full covariance matrices coordinating the different variables in the feature space. After learning (i.e., autonomous organization 
-%of the basis functions (position and spread), Gaussian mixture regression (GMR) is used to regenerate the nonlinear force profile. 
-%Sylvain Calinon, 2015
+% Enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture 
+% model (GMM) representation, with full covariance matrices coordinating the different variables 
+% in the feature space. After learning (i.e., autonomous organization of the basis functions (position 
+% and spread), Gaussian mixture regression (GMR) is used to regenerate the nonlinear force profile. 
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 5; %Number of states in the GMM
diff --git a/demo_DMP_GMR03.m b/demo_DMP_GMR03.m
index 9bf0c38da16545fc6980384ee24a51d61d7efe2e..36cbd9ff3921745192b0f0bcee062da5bda8dd06 100644
--- a/demo_DMP_GMR03.m
+++ b/demo_DMP_GMR03.m
@@ -1,12 +1,42 @@
 function demo_DMP_GMR03
-%Example of enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture model (GMM) representation, 
-%with full covariance matrices coordinating the different variables in the feature space. After learning (i.e., autonomous organization 
-%of the basis functions (position and spread), Gaussian mixture regression (GMR) is used to regenerate the path of a spring-damper system,
-%resulting in a nonlinear force profile. 
-%Sylvain Calinon, 2015
+% Enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture 
+% model (GMM) representation, with full covariance matrices coordinating the different variables 
+% in the feature space. After learning (i.e., autonomous organization of the basis functions 
+% (position and spread), Gaussian mixture regression (GMR) is used to regenerate the path of 
+% a spring-damper system, resulting in a nonlinear force profile. 
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 5; %Number of states in the GMM
diff --git a/demo_DMP_GMR04.m b/demo_DMP_GMR04.m
index 30b1aee66a8856ed86e7a89450f33f97ac76bdc3..539b168f4d5bef301825b17f88bd323449df1bc7 100644
--- a/demo_DMP_GMR04.m
+++ b/demo_DMP_GMR04.m
@@ -1,12 +1,43 @@
 function demo_DMP_GMR04
-%Example of enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture model (GMM) representation, 
-%with full covariance matrices coordinating the different variables in the feature space, and by using the task-parameterized model 
-%formalism. After learning (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
-%regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a nonlinear force profile. 
-%Sylvain Calinon, 2015
+% Enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture 
+% model (GMM) representation, with full covariance matrices coordinating the different variables 
+% in the feature space, and by using the task-parameterized model formalism. After learning 
+% (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
+% regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a 
+% nonlinear force profile. 
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 5; %Number of states in the GMM
diff --git a/demo_DMP_GMR_LQR01.m b/demo_DMP_GMR_LQR01.m
index bcf2620e4a3315749bfddfa3bce1cf811e1245c5..5b6621c4420345ccf92dfe2d1933209552e0668d 100644
--- a/demo_DMP_GMR_LQR01.m
+++ b/demo_DMP_GMR_LQR01.m
@@ -1,13 +1,44 @@
 function demo_DMP_GMR_LQR01
-%Example of enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture model (GMM) representation, 
-%with full covariance matrices coordinating the different variables in the feature space, and by using the task-parameterized model 
-%formalism. After learning (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
-%regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a nonlinear force profile.
-%The gains of the spring-damper system are further refined by LQR based on the retrieved covariance information.  
-%Sylvain Calinon, 2015
+% Enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture 
+% model (GMM) representation, with full covariance matrices coordinating the different variables 
+% in the feature space, and by using the task-parameterized model formalism. After learning 
+% (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
+% regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a 
+% nonlinear force profile. The gains of the spring-damper system are further refined by LQR 
+% based on the retrieved covariance information.  
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 5; %Number of states in the GMM
diff --git a/demo_DMP_GMR_LQR02.m b/demo_DMP_GMR_LQR02.m
index f4b03441e95d8722d8eb50dc738c0d6d229c9462..30edaa24c4c030c0fd349f0aa81b7d96b4290afe 100644
--- a/demo_DMP_GMR_LQR02.m
+++ b/demo_DMP_GMR_LQR02.m
@@ -1,15 +1,46 @@
 function demo_DMP_GMR_LQR02
-%Example of enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture model (GMM) representation, 
-%with full covariance matrices coordinating the different variables in the feature space, and by using the task-parameterized model 
-%formalism. After learning (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
-%regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a nonlinear force profile.
-%The gains of the spring-damper system are further refined by LQR based on the retrieved covariance information.
-%In this example, perturbations are added to show the benefit of encapsulating covariance information to coordinate 
-%disturbance rejection. 
-%Sylvain Calinon, 2015
+% Enhanced dynamic movement primitive (DMP) model trained with EM by using a Gaussian mixture 
+% model (GMM) representation, with full covariance matrices coordinating the different variables 
+% in the feature space, and by using the task-parameterized model formalism. After learning 
+% (i.e., autonomous organization of the basis functions (position and spread), Gaussian mixture 
+% regression (GMR) is used to regenerate the path of a spring-damper system, resulting in a 
+% nonlinear force profile. The gains of the spring-damper system are further refined by LQR 
+% based on the retrieved covariance information.  
+% In this example, perturbations are added to show the benefit of encapsulating covariance 
+% information to coordinate disturbance rejection. 
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 1; %Number of states in the GMM
diff --git a/demo_DSGMR01.m b/demo_DSGMR01.m
index d7a415e23e3a8b6920d49c6d944fa2a9c50374b5..20a6893caef78a46a28dc9665a7dc1fb135b9ed7 100644
--- a/demo_DSGMR01.m
+++ b/demo_DSGMR01.m
@@ -1,18 +1,35 @@
 function demo_DSGMR01
-% Gaussian mixture model (GMM), with Gaussian mixture regression(GMR) and dynamical systems used for reproduction,
-% with decay variable used as input (as in DMP).
+% Gaussian mixture model (GMM), with Gaussian mixture regression(GMR) and dynamical systems 
+% used for reproduction, with decay variable used as input (as in DMP).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_DTW01.m b/demo_DTW01.m
index e324bc24570bf9c1cb72fa7716923acad47b78bd..9cc026c86cc892b64fd0004ead427d41148f5c80 100644
--- a/demo_DTW01.m
+++ b/demo_DTW01.m
@@ -1,17 +1,34 @@
 function demo_DTW01
 % Trajectory realignment through dynamic time warping (DTW).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_GMM01.m b/demo_GMM01.m
index 551e647bd895aa9c20e57491fb391eca593254ee..0f2c5f25ab408bbe29d056dff212d3a802d2f354 100644
--- a/demo_GMM01.m
+++ b/demo_GMM01.m
@@ -1,17 +1,34 @@
 function demo_GMM01
 % Gaussian mixture model (GMM) parameters estimation.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_GMR01.m b/demo_GMR01.m
index bc1e27cbc644233fd1e6fdc94900c7b30578d727..c899a690466231eddba6a6250525dee096070878 100644
--- a/demo_GMR01.m
+++ b/demo_GMR01.m
@@ -1,17 +1,35 @@
 function demo_GMR01
-% Gaussian mixture model (GMM) with time-based Gaussian mixture regression (GMR) used for reproduction
+% Gaussian mixture model (GMM) with time-based Gaussian mixture regression (GMR) 
+% used for reproduction.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_GPR01.m b/demo_GPR01.m
index b981b5e07eb97414a190300a3931ba51961cd797..f1c377feeabaf67e3b08f8d96ac85fe46937bd0d 100644
--- a/demo_GPR01.m
+++ b/demo_GPR01.m
@@ -1,17 +1,35 @@
 function demo_GPR01
-% Gaussian processs regression (GPR) used for task adaptation, with DS-GMR employed to retrieve continuous movements
+% Gaussian processs regression (GPR) used for task adaptation, with DS-GMR used to 
+% retrieve continuous movements.
 % 
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_HDDC01.m b/demo_HDDC01.m
index 0139babfe678dffad56a0ca66c755550944c2843..73d427ade0a430bcbcae38e221638567e93ec17a 100644
--- a/demo_HDDC01.m
+++ b/demo_HDDC01.m
@@ -1,17 +1,44 @@
 function demo_HDDC01
-% Example of High Dimensional Data Clustering (HDDC, or HD-GMM) encoding from Bouveyron (2007)
+% High Dimensional Data Clustering (HDDC, or HD-GMM) encoding.
 % 
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% @article{Bouveyron07,
+% 	author = "Bouveyron, C. and Girard, S. and Schmid, C.",
+% 	title = "High-dimensional data clustering",
+% 	journal = "Computational Statistics and Data Analysis",
+% 	year = "2007",
+% 	volume = "52",
+% 	number = "1",
+% 	pages = "502--519"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_MFA01.m b/demo_MFA01.m
index a9ca0913a2f86bd1d7d972b301bae7dcdcdf0b57..eccebcb08b6c0833e56b9726d60dbaca3417ef11 100644
--- a/demo_MFA01.m
+++ b/demo_MFA01.m
@@ -1,17 +1,34 @@
 function demo_MFA01
-% Mixture of factor analysers (MFA) encoding
+% Mixture of factor analysers (MFA) encoding.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_MPPCA01.m b/demo_MPPCA01.m
index 5106a1bb29b3bbec3750dafd6c2af3a753254497..7104043a9f3e1e93df7be64aa0348412756a5de4 100644
--- a/demo_MPPCA01.m
+++ b/demo_MPPCA01.m
@@ -1,20 +1,38 @@
 function demo_MPPCA01
-% Example of mixture of probabilistic principal component analyzers (MPPCA) encoding
+% Mixture of probabilistic principal component analyzers (MPPCA) encoding.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 4; %Number of states in the GMM
diff --git a/demo_TPGMM01.m b/demo_TPGMM01.m
index 37b3fd7b253b4a5e20ac9cbce4cfdc0b365c8578..237625510d652cc76ba9c13b09ce04af6f322e71 100644
--- a/demo_TPGMM01.m
+++ b/demo_TPGMM01.m
@@ -1,17 +1,34 @@
 function demo_TPGMM01
-% Task-parameterized Gaussian mixture model (TP-GMM) encoding
+% Task-parameterized Gaussian mixture model (TP-GMM) encoding.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPGMR01.m b/demo_TPGMR01.m
index f253007dc6a07bc81b4aa72ab2b0f3d81ed74477..9a39ea2593684e7e4a649fb9d701c8d60f4e37c6 100644
--- a/demo_TPGMR01.m
+++ b/demo_TPGMR01.m
@@ -1,17 +1,34 @@
 function demo_TPGMR01
-% Task-parameterized Gaussian mixture model (TP-GMM), with time-based GMR used for reproduction 
+% Task-parameterized Gaussian mixture model (TP-GMM), with time-based GMR used for reproduction. 
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPGMR_DS01.m b/demo_TPGMR_DS01.m
index 1c45fe78473987e0f971e9d68d924669540d9abf..ecc0bc703ab2285cb1d65741543bee3159b49085 100644
--- a/demo_TPGMR_DS01.m
+++ b/demo_TPGMR_DS01.m
@@ -1,20 +1,25 @@
 function demo_TPGMR_DS01
-% Demonstration a task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
+% Task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
 % systems acting in multiple frames of reference. Each candidate coordinate system observes a set of
 % demonstrations from its own perspective, by extracting an attractor path whose variations depend on the
 % relevance of the frame through the task. This information is exploited to generate a new attractor path
 % corresponding to new situations (new positions and orientation of the frames).
-%
 % This example presents the results for a time-based GMR reference retrieval process combined with a tracking system 
 % with constant gains.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
 %
-% @inproceedings{Calinon14ICRA,
+% @inproceedings{Calinon14,
 %   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
 %   title="A task-parameterized probabilistic model with minimal intervention control",
 %   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
@@ -23,6 +28,23 @@ function demo_TPGMR_DS01
 %   address="Hong Kong, China",
 %   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPGMR_LQR01.m b/demo_TPGMR_LQR01.m
index 70b5025e2615d36506634ae8afe6104945804480..6538de50a01d7535975202af84d964268665be2f 100644
--- a/demo_TPGMR_LQR01.m
+++ b/demo_TPGMR_LQR01.m
@@ -1,21 +1,26 @@
 function demo_TPGMR_LQR01
-% Demonstration a task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
+% Task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
 % systems acting in multiple frames of reference. Each candidate coordinate system observes a set of
 % demonstrations from its own perspective, by extracting an attractor path whose variations depend on the
 % relevance of the frame through the task. This information is exploited to generate a new attractor path
 % corresponding to new situations (new positions and orientation of the frames), while the predicted covariances
 % are exploited by a linear quadratic regulator (LQR) to estimate the stiffness and damping feedback terms of
 % the spring-damper systems, resulting in a minimal intervention control strategy.
-%
 % This example presents the results for a time-based GMR reference retrieval process combined with a finite horizon LQR.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
 %
-% @inproceedings{Calinon14ICRA,
+% @inproceedings{Calinon14,
 %   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
 %   title="A task-parameterized probabilistic model with minimal intervention control",
 %   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
@@ -24,6 +29,23 @@ function demo_TPGMR_LQR01
 %   address="Hong Kong, China",
 %   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPGMR_LQR02.m b/demo_TPGMR_LQR02.m
index 05294a1057d0a2da7e152e6fe1dd997d093dc5f7..125a15931f689839eeb9fe353b58618a9830462d 100644
--- a/demo_TPGMR_LQR02.m
+++ b/demo_TPGMR_LQR02.m
@@ -1,21 +1,26 @@
 function demo_TPGMR_LQR02
-% Demonstration a task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
+% Task-parameterized probabilistic model encoding movements in the form of virtual spring-damper
 % systems acting in multiple frames of reference. Each candidate coordinate system observes a set of
 % demonstrations from its own perspective, by extracting an attractor path whose variations depend on the
 % relevance of the frame through the task. This information is exploited to generate a new attractor path
 % corresponding to new situations (new positions and orientation of the frames), while the predicted covariances
 % are exploited by a linear quadratic regulator (LQR) to estimate the stiffness and damping feedback terms of
 % the spring-damper systems, resulting in a minimal intervention control strategy.
-%
 % This example presents the results for a time-based GMR reference retrieval process combined with an infinite horizon LQR.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
 %
-% @inproceedings{Calinon14ICRA,
+% @inproceedings{Calinon14,
 %   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
 %   title="A task-parameterized probabilistic model with minimal intervention control",
 %   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
@@ -24,6 +29,23 @@ function demo_TPGMR_LQR02
 %   address="Hong Kong, China",
 %   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPGP01.m b/demo_TPGP01.m
index a2b17933b61c9faa3b9869223bf401d711545056..3bb5ecc0194ed4b3e76f63ab3199c0ed71902bb7 100644
--- a/demo_TPGP01.m
+++ b/demo_TPGP01.m
@@ -1,17 +1,34 @@
 function demo_TPGP01
-% Task-parameterized Gaussian process regression (TP-GPR)
+% Task-parameterized Gaussian process regression (TP-GPR).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPHDDC01.m b/demo_TPHDDC01.m
index 7db387c26148aef2c807af67708df96e7a4cde29..bf1d91da730f418c6d0df0088340b01b49336bda 100644
--- a/demo_TPHDDC01.m
+++ b/demo_TPHDDC01.m
@@ -1,17 +1,34 @@
 function demo_TPHDDC01
-% Task-parameterized high dimensional data clustering (TP-HDDC)
+% Task-parameterized high dimensional data clustering (TP-HDDC).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPMFA01.m b/demo_TPMFA01.m
index 29fb85d616306e11abee04ae28bf3c6a072a7772..b87591e885a92ec93cfef878dbe700a75650008d 100644
--- a/demo_TPMFA01.m
+++ b/demo_TPMFA01.m
@@ -1,17 +1,34 @@
 function demo_TPMFA01
-% Task-parameterized mixture of factor analyzers (TP-MFA)
+% Task-parameterized mixture of factor analyzers (TP-MFA).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPMPC01.m b/demo_TPMPC01.m
index 242d50560396b7b8d45840d115aeca933d6f5b71..d1d9c527f30c7fcf7f4ac3be78722982b43a477c 100644
--- a/demo_TPMPC01.m
+++ b/demo_TPMPC01.m
@@ -1,10 +1,39 @@
 function demo_TPMPC01
 % Task-parameterized probabilistic model encoding position data, with MPC (batch version of LQR) 
-% used to track the associated stepwise reference path
-% Sylvain Calinon, 2015
+% used to track the associated stepwise reference path.
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 3; %Number of Gaussians in the GMM
@@ -188,5 +217,5 @@ end
 axis(limAxes); axis square; set(gca,'xtick',[],'ytick',[]);
 
 %print('-dpng','graphs/demo_TPMPC01.png');
-pause;
-close all;
+%pause;
+%close all;
diff --git a/demo_TPMPC02.m b/demo_TPMPC02.m
index 80a3665c12ee016c2e71f61fd8406fa7271efb8a..fc4b36ef4f865eb2c45c1141a5147bca6f449083 100644
--- a/demo_TPMPC02.m
+++ b/demo_TPMPC02.m
@@ -1,7 +1,35 @@
 function demo_TPMPC02
 % Task-parameterized probabilistic model encoding position data, with a generalized version of MPC 
-% (batch version of LQR) used to track associated stepwise reference paths in multiple frames
-% Sylvain Calinon, 2015
+% (batch version of LQR) used to track associated stepwise reference paths in multiple frames.
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
@@ -217,5 +245,5 @@ end
 axis(limAxes); axis square; set(gca,'xtick',[],'ytick',[]);
 
 %print('-dpng','graphs/demo_TPMPC02.png');
-pause;
-close all;
+%pause;
+%close all;
diff --git a/demo_TPMPPCA01.m b/demo_TPMPPCA01.m
index 847f3135e282e3e50d7b41624191129580be336e..a98336299e54450c490d4d4c2e28d3ed4856f398 100644
--- a/demo_TPMPPCA01.m
+++ b/demo_TPMPPCA01.m
@@ -1,17 +1,34 @@
 function demo_TPMPPCA01
-% Task-parameterized mixture of probabilistic principal component analyzers (TP-MPPCA) 
+% Task-parameterized mixture of probabilistic principal component analyzers (TP-MPPCA). 
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPbatchLQR01.m b/demo_TPbatchLQR01.m
index 0b3fd3225e30b8abf3f444f6e9a6c5beafb5f7b6..1a69d0268cb720cff3126af5e29e3d9757e4d3c6 100644
--- a/demo_TPbatchLQR01.m
+++ b/demo_TPbatchLQR01.m
@@ -1,18 +1,35 @@
 function demo_TPbatchLQR01
 % Task-parameterized GMM encoding position and velocity data, combined with a batch solution 
-% of linear quadratic optimal control (unconstrained linear MPC)
+% of linear quadratic optimal control (unconstrained linear MPC).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPbatchLQR02.m b/demo_TPbatchLQR02.m
index 42a9176ca94b478bfbe711e61e38e1e8427be6bf..913a58562872dc22ced803559a518b424432adf2 100644
--- a/demo_TPbatchLQR02.m
+++ b/demo_TPbatchLQR02.m
@@ -1,18 +1,35 @@
 function demo_TPbatchLQR02
 % Batch solution of a linear quadratic optimal control (unconstrained linear MPC) acting in multiple frames,
-% which is equivalent to TP-GMM combined with LQR
+% which is equivalent to TP-GMM combined with LQR.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_TPtrajGMM01.m b/demo_TPtrajGMM01.m
index 81d49a47f5ea1d1d7f23f37d595a18883007c2e3..93df72fc5447d691df22aa17808291ba014542d6 100644
--- a/demo_TPtrajGMM01.m
+++ b/demo_TPtrajGMM01.m
@@ -1,17 +1,34 @@
 function demo_TPtrajGMM01
-% Task-parameterized model with trajectory-GMM encoding (GMM with dynamic features)
+% Task-parameterized model with trajectory-GMM encoding (GMM with dynamic features).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_affineTransform01.m b/demo_affineTransform01.m
index d085c526e5585c15acad5e026610d339170b55ee..eb4f16ac47d0548a0a77421229911287ba18333e 100644
--- a/demo_affineTransform01.m
+++ b/demo_affineTransform01.m
@@ -1,17 +1,34 @@
 function demo_affineTransform01
-% Miscellaneous affine transformations of raw data as pre-processing step to train a task-parameterized model 
+% Affine transformations of raw data as pre-processing step to train a task-parameterized model. 
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_batchLQR01.m b/demo_batchLQR01.m
index 553085dd3d7e45c7b5320c3773257f1fc0306257..795644c0cf85a05b4cc4d4c7d076cbea7a7d2b8b 100644
--- a/demo_batchLQR01.m
+++ b/demo_batchLQR01.m
@@ -2,17 +2,34 @@ function demo_batchLQR01
 % Controller retrieval through a batch solution of linear quadratic optimal control (unconstrained linear MPC),
 % by relying on a Gaussian mixture model (GMM) encoding of position and velocity data.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_batchLQR02.m b/demo_batchLQR02.m
index 91908f1f1fa8b19f4904192e62ec6e470e58d558..e5d946ef2e76a1778718e48486484de5c0e721ab 100644
--- a/demo_batchLQR02.m
+++ b/demo_batchLQR02.m
@@ -2,17 +2,34 @@ function demo_batchLQR02
 % Controller retrieval through a batch solution of linear quadratic optimal control (unconstrained linear MPC),
 % by relying on a Gaussian mixture model (GMM) encoding of only position.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_iterativeLQR01.m b/demo_iterativeLQR01.m
index b3db7f440d1894d53ca4b26b01a364d7ad20d1c7..d31676610c052e3fedfe7e4eacfd667b9cddad83 100644
--- a/demo_iterativeLQR01.m
+++ b/demo_iterativeLQR01.m
@@ -1,21 +1,50 @@
 function demo_iterativeLQR01
-% Example of controller retrieval through an iterative solution of linear quadratic optimal control (finite horizon, 
-% unconstrained linear MPC), by relying on a Gaussian mixture model (GMM) encoding of position and velocity data
+% Controller retrieval through an iterative solution of linear quadratic optimal control (finite horizon, 
+% unconstrained linear MPC), by relying on a Gaussian mixture model (GMM) encoding of position and velocity data, 
+% including comparison with batch LQR.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+%
+% @inproceedings{Calinon14,
+%   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
+%   title="A task-parameterized probabilistic model with minimal intervention control",
+%   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
+%   year="2014",
+%   month="May-June",
+%   address="Hong Kong, China",
+%   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 nbSamples = 3; %Number of demonstrations
diff --git a/demo_iterativeLQR02.m b/demo_iterativeLQR02.m
index da9eea02780ba1063c7eeac0aed6182e450f0fc6..49f6a780790289420c6935a9c3edca3087dc3931 100644
--- a/demo_iterativeLQR02.m
+++ b/demo_iterativeLQR02.m
@@ -1,21 +1,49 @@
 function demo_iterativeLQR02
 % Controller retrieval through an iterative solution of linear quadratic optimal control (finite horizon, 
-% unconstrained linear MPC), by relying on a Gaussian mixture model (GMM) encoding of only position data
+% unconstrained linear MPC), by relying on a Gaussian mixture model (GMM) encoding of only position data.
 %
-% Sylvain Calinon, Danilo Bruno, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, we would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+%
+% @inproceedings{Calinon14,
+%   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
+%   title="A task-parameterized probabilistic model with minimal intervention control",
+%   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
+%   year="2014",
+%   month="May-June",
+%   address="Hong Kong, China",
+%   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 nbSamples = 3; %Number of demonstrations
diff --git a/demo_stdPGMM01.m b/demo_stdPGMM01.m
index 3faf987c5bc0056c89dc43b10da66c53ccb71c10..98b5995e7da17255c4ad468a19b5fcebcaf763ff 100644
--- a/demo_stdPGMM01.m
+++ b/demo_stdPGMM01.m
@@ -1,18 +1,35 @@
 function demo_stdPGMM01
-% Example of parametric Gaussian mixture model (PGMM) used for task adaptation,
-% with DS-GMR employed to retrieve continuous movements
+% Parametric Gaussian mixture model (PGMM) used for task adaptation,
+% with DS-GMR employed to retrieve continuous movements.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_testDampingRatio01.m b/demo_testDampingRatio01.m
index 01b48289037ede27f1e2fd85f166d5141a404bf9..a9e12eb3565f3ed4b6e1a9b137ac97ec690425fd 100644
--- a/demo_testDampingRatio01.m
+++ b/demo_testDampingRatio01.m
@@ -1,7 +1,38 @@
 function demo_testDampingRatio01
-% Test of the differences between critically damped systems and ideal underdamped systems
-%	Sylvain Calinon, 2015
+% Behaviors of critically damped systems and ideal underdamped systems.
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
+
+%% Parameters
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 nbData = 100; %Number of datapoints
 kp = 200; %Stiffness
 kv = 2*kp^.5; %Damping for critically damped system
@@ -9,6 +40,9 @@ kv2 = (2*kp)^.5; %Damping for ideal underdamped system
 xhat = 1; %Desired target
 dt = 0.01; %Time step
 
+
+%% Simulation
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 %Computation of tracking error for critically damped system
 x=0; dx=0; e=0;
 for t=1:nbData
@@ -31,16 +65,18 @@ for t=1:nbData
 end
 disp(['Cumulated tracking error for ideal underdamped system: ' num2str(e)]);
 
-%Plot
+%% Plots
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 figure; hold on;
 plot([1:nbData]*dt, Data(1,:), 'k-');
 plot([1:nbData]*dt, Data2(1,:), 'k:');
 legend('critically damped', 'ideal underdamped');
 plot([1,nbData]*dt, [xhat,xhat], 'r-');
 xlabel('t'); ylabel('x');
-	
-pause;
-close all;
+
+%print('-dpng','graphs/demo_testDampingRatio01.png');
+%pause;
+%close all;
 	
 	
 	
diff --git a/demo_testLQR01.m b/demo_testLQR01.m
index 5562cf2762ca754e0419b6c4b2251a4c2ed2b2aa..6bf7bb2e22d72275615ad4218dd99375049cf637 100644
--- a/demo_testLQR01.m
+++ b/demo_testLQR01.m
@@ -1,17 +1,44 @@
 function demo_testLQR01
-% Test of the linear quadratic regulation with different variance in the data
+% Test of the linear quadratic regulation with different variance in the data.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+%
+% @inproceedings{Calinon14,
+%   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
+%   title="A task-parameterized probabilistic model with minimal intervention control",
+%   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
+%   year="2014",
+%   month="May-June",
+%   address="Hong Kong, China",
+%   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_testLQR02.m b/demo_testLQR02.m
index 93bb4982d1366eb97b3d3fd65352bfb8ee4019eb..223dc7fe902945b7222e34732d9a85200a8c9f8d 100644
--- a/demo_testLQR02.m
+++ b/demo_testLQR02.m
@@ -1,17 +1,44 @@
 function demo_testLQR02
-% Test of the linear quadratic regulation (evaluation of the damping ratio found by the system)
+% Test of the linear quadratic regulation (evaluation of the damping ratio found by the system).
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+%
+% @inproceedings{Calinon14,
+%   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
+%   title="A task-parameterized probabilistic model with minimal intervention control",
+%   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
+%   year="2014",
+%   month="May-June",
+%   address="Hong Kong, China",
+%   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_testLQR03.m b/demo_testLQR03.m
index 165e4567d1f52aef937c1992df0538e28362d47c..3d36e31b36055c78b3eae7c23b643239d8267aae 100644
--- a/demo_testLQR03.m
+++ b/demo_testLQR03.m
@@ -1,13 +1,19 @@
 function demo_testLQR03
-% Comparison of linear quadratic regulators with finite and infinite time horizons
+% Comparison of linear quadratic regulators with finite and infinite time horizons.
 %
-% Author:	Sylvain Calinon, 2014
-%         http://programming-by-demonstration.org/SylvainCalinon
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
 %
-% @inproceedings{Calinon14ICRA,
+% @inproceedings{Calinon14,
 %   author="Calinon, S. and Bruno, D. and Caldwell, D. G.",
 %   title="A task-parameterized probabilistic model with minimal intervention control",
 %   booktitle="Proc. {IEEE} Intl Conf. on Robotics and Automation ({ICRA})",
@@ -16,6 +22,23 @@ function demo_testLQR03
 %   address="Hong Kong, China",
 %   pages="3339--3344"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon (http://calinon.ch/) and Danilo Bruno (danilo.bruno@iit.it)
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_testLQR04.m b/demo_testLQR04.m
index 3f521e8cd1b741ef362a2a9f57a2ffe9a769c42b..91d6113354888264fd4dbaf896047dcb195ceac1 100644
--- a/demo_testLQR04.m
+++ b/demo_testLQR04.m
@@ -2,17 +2,34 @@ function demo_testLQR04
 % Demonstration of the coordination capability of linear quadratic optimal control 
 % (unconstrained linear MPC) combined with full precision matrices.
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
diff --git a/demo_trajGMM01.m b/demo_trajGMM01.m
index 153263dcd5f631d4fc4183f994e11d4566f446b2..9c1984a4746eda0e9ec68f82a3765a3c0ec75596 100644
--- a/demo_trajGMM01.m
+++ b/demo_trajGMM01.m
@@ -1,6 +1,35 @@
 function demo_trajGMM01
-% Trajectory synthesis with a GMM with dynamic features (trajectory GMM)
-% Sylvain Calinon, 2015
+% Trajectory synthesis with a GMM with dynamic features (trajectory GMM).
+%
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
+%
+% @article{Calinon15,
+%   author="Calinon, S.",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
+% }
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
+
 
 addpath('./m_fcts/');
 
@@ -43,7 +72,7 @@ end
 
 %Re-arrange data in vector form
 x = reshape(Data, model.nbVarPos*nbData*nbSamples, 1) * 1E2; %Scale data to avoid numerical computation problem
-zeta = PHI*x; %y is for example [x1(1), x2(1), x1d(1), x2d(1), x1(2), x2(2), x1d(2), x2d(2), ...], see Eq. (2.4.5) in doc/TechnicalReport.pdf
+zeta = PHI*x; %y is for example [x1(1), x2(1), x1d(1), x2d(1), x1(2), x2(2), x1d(2), x2d(2), ...]
 Data = reshape(zeta, model.nbVarPos*model.nbDeriv, nbData*nbSamples); %Include derivatives in Data
 
 
@@ -75,7 +104,7 @@ for n=1:1 %nbSamples
 	%Compute best path for the n-th demonstration
 	[~,r(n).q] = max(GAMMA2(:,(n-1)*nbData+1:n*nbData),[],1); %works also for nbStates=1
 	
-	%Create single Gaussian N(MuQ,SigmaQ) based on optimal state sequence q, see Eq. (2.4.8) in doc/TechnicalReport.pdf
+	%Create single Gaussian N(MuQ,SigmaQ) based on optimal state sequence q
 	MuQ = reshape(model.Mu(:,r(n).q), model.nbVar*nbData, 1); 
 	%MuQ = zeros(model.nbVar*nbData,1);
 	SigmaQ = zeros(model.nbVar*nbData);
@@ -88,13 +117,13 @@ for n=1:1 %nbSamples
 	%SigmaQ = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model.Sigma(:,:,r(n).q), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar));
 
 
-% 	%Least squares computation method 1 (using lscov Matlab function), see Eq. (2.4.11) in doc/TechnicalReport.pdf
-% 	%%%%%%%%%%%%%%%%%%%
-% 	[zeta,~,mse,S] = lscov(PHI1, MuQ, SigmaQ, 'chol'); %Retrieval of data with weighted least squares solution
-% 	r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
+	%Least squares computation method 1 (using lscov Matlab function)
+	%%%%%%%%%%%%%%%%%%%
+	[zeta,~,mse,S] = lscov(PHI1, MuQ, SigmaQ, 'chol'); %Retrieval of data with weighted least squares solution
+	r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
 
 	
-% 	%Least squares computation method 2 (most readable but not optimized), see Eq. (2.4.11) in doc/TechnicalReport.pdf
+% 	%Least squares computation method 2 (most readable but not optimized)
 % 	%%%%%%%%%%%%%%%%%%%
 % 	PHIinvSigmaQ = PHI1' / SigmaQ;
 % 	Rq = PHIinvSigmaQ * PHI1;
@@ -102,32 +131,29 @@ for n=1:1 %nbSamples
 % 	zeta = Rq \ rq; %Can also be computed with c = lscov(Rq, rq)
 % 	size(zeta)
 % 	r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
-% 	%Covariance Matrix computation of ordinary least squares estimate, see Eq. (2.4.12) in doc/TechnicalReport.pdf
+% 	%Covariance Matrix computation of ordinary least squares estimate
 % 	mse =  (MuQ'*inv(SigmaQ)*MuQ - rq'*inv(Rq)*rq) ./ ((model.nbVar-model.nbVarPos)*nbData);
 % 	S = inv(Rq) * mse; 
 	
 
-	%Least squares computation method 3 (efficient computation using Cholesky and QR decompositions, inspired by lscov code)
-	%%%%%%%%%%%%%%%%%%%
-	T = chol(SigmaQ)'; %SigmaQ=T*T'
-	TA = T \ PHI1;
-	TMuQ = T \ MuQ;
-	[Q, R, perm] = qr(TA,0); %PHI1(:,perm)=Q*R
-	z = Q' * TMuQ;
-	zeta = zeros(nbData*model.nbVarPos,1);
-	zeta(perm,:) = R \ z; %zeta=(TA'*TA)\(TA'*TMuQ), see Eq. (2.4.11) in doc/TechnicalReport.pdf
-	r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
-	%Covariance Matrix computation of ordinary least squares estimate
-	err = TMuQ - Q*z;
-	norm(err)
-	norm(eye(size(Q,2)) - Q'*Q)
-	return
-	mse = err'*err ./ (model.nbVar*nbData - model.nbVarPos*nbData);
-	Rinv = R \ eye(model.nbVarPos*nbData);
-	S(perm,perm) = Rinv*Rinv' .* mse; %See Eq. (2.4.12) in doc/TechnicalReport.pdf
+% 	%Least squares computation method 3 (efficient computation using Cholesky and QR decompositions, inspired by lscov code)
+% 	%%%%%%%%%%%%%%%%%%%
+% 	T = chol(SigmaQ)'; %SigmaQ=T*T'
+% 	TA = T \ PHI1;
+% 	TMuQ = T \ MuQ;
+% 	[Q, R, perm] = qr(TA,0); %PHI1(:,perm)=Q*R
+% 	z = Q' * TMuQ;
+% 	zeta = zeros(nbData*model.nbVarPos,1);
+% 	zeta(perm,:) = R \ z; %zeta=(TA'*TA)\(TA'*TMuQ)
+% 	r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
+% 	%Covariance Matrix computation of ordinary least squares estimate
+% 	err = TMuQ - Q*z;
+% 	mse = err'*err ./ (model.nbVar*nbData - model.nbVarPos*nbData);
+% 	Rinv = R \ eye(model.nbVarPos*nbData);
+% 	S(perm,perm) = Rinv*Rinv' .* mse; 
 	
 	
-	%Rebuild covariance by reshaping S, see Eq. (2.4.12) in doc/TechnicalReport.pdf
+	%Rebuild covariance by reshaping S
 	for t=1:nbData
 		id = (t-1)*model.nbVarPos+1:t*model.nbVarPos;
 		r(n).expSigma(:,:,t) = S(id,id) * nbData;
diff --git a/demo_trajMFA01.m b/demo_trajMFA01.m
index aa076eccac33e767cb783fecd4e21ee52f317847..9554e4a7c3c93a7e5df0d9dbd4592eae5f37c6bb 100644
--- a/demo_trajMFA01.m
+++ b/demo_trajMFA01.m
@@ -1,24 +1,41 @@
 function demo_trajMFA01
-% Trajectory model with either (see lines 69-71): 
+% Trajectory model with either (see lines 79-81): 
 %  -a mixture of factor analysers (MFA)
 %  -a mixture of probabilistic principal component analyzers (MPPCA)
-%  -a high-fimensional data clustering approach proposed by Bouveyron (HD-GMM)
+%  -a high-dimensional data clustering approach proposed by Bouveyron (HD-GMM)
 %
-% Sylvain Calinon, 2015
-% http://programming-by-demonstration.org/lib/
-%
-% This source code is given for free! In exchange, I would be grateful if you cite
-% the following reference in any academic publication that uses this code or part of it:
+% Writing code takes time. Polishing it and making it available to others takes longer! 
+% If some parts of the code were useful for your research of for a better understanding 
+% of the algorithms, please reward the authors by citing the related publications, 
+% and consider making your own research available in this way.
 %
 % @article{Calinon15,
 %   author="Calinon, S.",
-%   title="A tutorial on task-parameterized movement learning and retrieval",
-%   year="2015",
+%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
+%   journal="Intelligent Service Robotics",
+%   year="2015"
 % }
-
+% 
+% Copyright (c) 2015 Idiap Research Institute, http://idiap.ch/
+% Written by Sylvain Calinon, http://calinon.ch/
+% 
+% This file is part of PbDlib, http://www.idiap.ch/software/pbdlib/
+% 
+% PbDlib is free software: you can redistribute it and/or modify
+% it under the terms of the GNU General Public License version 3 as
+% published by the Free Software Foundation.
+% 
+% PbDlib is distributed in the hope that it will be useful,
+% but WITHOUT ANY WARRANTY; without even the implied warranty of
+% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+% GNU General Public License for more details.
+% 
+% You should have received a copy of the GNU General Public License
+% along with PbDlib. If not, see <http://www.gnu.org/licenses/>.
 
 addpath('./m_fcts/');
 
+
 %% Parameters
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model.nbStates = 3; %Number of components in the mixture model
@@ -27,181 +44,69 @@ model.nbVarPos = 4; %Dimension of the position datapoint
 model.nbDeriv = 3; %Nb derivatives+1 (D=2 for [x,dx], D=3 for [x,dx,ddx], etc.)
 model.nbVar = model.nbVarPos * model.nbDeriv;
 model.dt = 1; %Time step (large values such as 1 will tend to create clusers by following position information)
-nbD = 100; %Number of datapoints in a trajectory
+nbData = 100; %Number of datapoints in a trajectory
 nbSamples = 1; %Number of trajectory samples
 
-%Construct operator A (big sparse matrix)
-T1 = nbD; %Number of datapoints in a demonstration
-T = T1 * nbSamples; %Total number of datapoints
-op1D = zeros(model.nbDeriv);
-op1D(1,end) = 1;
-for i=2:model.nbDeriv
-	op1D(i,:) = (op1D(i-1,:) - circshift(op1D(i-1,:),[0,-1])) / model.dt;
-end
-op = zeros(T1*model.nbDeriv,T1);
-op((model.nbDeriv-1)*model.nbDeriv+1:model.nbDeriv*model.nbDeriv,1:model.nbDeriv) = op1D;
-A0 = zeros(T1*model.nbDeriv,T1);
-for t=0:T1-model.nbDeriv
-	A0 = A0 + circshift(op, [model.nbDeriv*t,t]);
-end
-%Handling of borders
-for i=1:model.nbDeriv-1
-	op(model.nbDeriv*model.nbDeriv+1-i,:)=0; op(:,i)=0;
-	A0 = A0 + circshift(op, [-i*model.nbDeriv,-i]);
-end
-%Application to multiple dimensions and multiple demonstrations
-A1 = kron(A0, eye(model.nbVarPos));
-A = kron(eye(nbSamples), A1);
+[PHI,PHI1] = constructPHI(model,nbData,nbSamples); %Construct PHI operator (big sparse matrix)
 
 
-%% Load data
+%% Load AMARSI handwriting data
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-% Data = grabDataFromCursor;
-% save('data/dataTrajGMM05.mat','Data');
-
-load('data/data03.mat');
-
-%Resampling
-nbD0 = size(Data,2)/nbSamples; %Original number of datapoints in a trajectory
-DataTmp = [];
+demos=[];
+load('data/AMARSI/GShape.mat'); %Load x1,x2 variables
 for n=1:nbSamples
-	DataTmp = [DataTmp spline(1:nbD0, Data(:,(n-1)*nbD0+1:n*nbD0), linspace(1,nbD0,nbD))]; 
+	s(n).Data = spline(1:size(demos{n}.pos,2), demos{n}.pos, linspace(1,size(demos{n}.pos,2),nbData)); %Resampling
 end
-Data = DataTmp;
-
-%Compute derivatives [x;dx;ddx]
-D = (diag(ones(1,nbD-1),-1)-eye(nbD)) / model.dt;
-D(end,end) = 0;
-for k=1:model.nbDeriv-1
-	Data = [Data; Data(1:model.nbVarPos,:)*D^k]; %Compute derivatives
+demos=[];
+load('data/AMARSI/CShape.mat'); %Load x3,x4 variables
+Data=[];
+for n=1:nbSamples
+	s(n).Data = [s(n).Data; spline(1:size(demos{n}.pos,2), demos{n}.pos, linspace(1,size(demos{n}.pos,2),nbData))]; %Resampling
+	Data = [Data s(n).Data]; 
 end
 
 %Re-arrange data in vector form
-x = reshape(Data(1:model.nbVarPos,:), model.nbVarPos*T, 1) * 1E2; %1E2 to avoid numerical problem
-y = A*x; %y is for example [x1(1), x2(1), x1d(1), x2d(1), x1(2), x2(2), x1d(2), x2d(2), ...]
-Data = reshape(y, model.nbVar, T); %Include derivatives in Data
+x = reshape(Data, model.nbVarPos*nbData*nbSamples, 1) * 1E2; %Scale data to avoid numerical computation problem
+zeta = PHI*x; %y is for example [x1(1), x2(1), x1d(1), x2d(1), x1(2), x2(2), x1d(2), x2d(2), ...], see Eq. (2.4.5) in doc/TechnicalReport.pdf
+Data = reshape(zeta, model.nbVarPos*model.nbDeriv, nbData*nbSamples); %Include derivatives in Data
 
 
 %% Learning
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 model = init_GMM_kmeans(Data, model);
 
-[model, GAMMA2] = EM_GMM(Data, model);
-%[model, GAMMA2] = EM_MFA(Data, model);
+%[model, GAMMA2] = EM_GMM(Data, model);
+[model, GAMMA2] = EM_MFA(Data, model);
 %[model, GAMMA2] = EM_MPPCA(Data, model);
 %[model, GAMMA2] = EM_HDGMM(Data, model);
 
 
-%% Batch reconstruction
+%% Reconstruction
 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-[~,r(1).q] = max(GAMMA2,[],1); %works also for nbStates=1
-%Create single Gaussian N(MuQ,SigmaQ) based on state sequence q
-r(1).MuQ = reshape(model.Mu(:,r(1).q), model.nbVar*T1, 1);
-r(1).SigmaQ = zeros(model.nbVar*T1);
-for t=1:T1
-	id1 = (t-1)*model.nbVar+1:t*model.nbVar;
-	r(1).SigmaQ(id1,id1) = model.Sigma(:,:,r(1).q(t));
-end
-%r(1).SigmaQ = (kron(ones(T1,1), eye(model.nbVar)) * reshape(model.Sigma(:,:,r(1).q), model.nbVar, model.nbVar*T1)) ...
-%		.* kron(eye(T1), ones(model.nbVar));
-
-% %Retrieval of data with trajectory GMM (non-optimized computation)
-% AinvSigmaQ = A1'/r(1).SigmaQ;
-% Rq = AinvSigmaQ * A1;
-% rq = AinvSigmaQ * r(1).MuQ;
-% r(1).Data = reshape(Rq\rq, model.nbVarPos, T1); %Reshape data for plotting
-
-%Retrieval of data with weighted least squares solution
-[c,~,~,S] = lscov(A1, r(1).MuQ, r(1).SigmaQ, 'chol');
-r(n).Data = reshape(c, model.nbVarPos, T1); %Reshape data for plotting	
-for t=1:T1
-	id = (t-1)*model.nbVarPos+1:t*model.nbVarPos;
-	r(1).expSigma(:,:,t) = S(id,id) * T1;
+%Compute best path for the n-th demonstration
+[~,r(1).q] = max(GAMMA2(:,1:nbData),[],1); %works also for nbStates=1
+
+%Create single Gaussian N(MuQ,SigmaQ) based on optimal state sequence q, see Eq. (2.4.8) in doc/TechnicalReport.pdf
+MuQ = reshape(model.Mu(:,r(1).q), model.nbVar*nbData, 1); 
+%MuQ = zeros(model.nbVar*nbData,1);
+SigmaQ = zeros(model.nbVar*nbData);
+for t=1:nbData
+	id = (t-1)*model.nbVar+1:t*model.nbVar;
+	%MuQ(id) = model.Mu(:,r(n).q(t)); 
+	SigmaQ(id,id) = model.Sigma(:,:,r(1).q(t));
 end
+%SigmaQ can alternatively be computed with:
+%SigmaQ = (kron(ones(nbData,1), eye(model.nbVar)) * reshape(model.Sigma(:,:,r(1).q), model.nbVar, model.nbVar*nbData)) .* kron(eye(nbData), ones(model.nbVar));
 
+%Least squares computation
+[zeta,~,mse,S] = lscov(PHI1, MuQ, SigmaQ, 'chol'); %Retrieval of data with weighted least squares solution
+r(n).Data = reshape(zeta, model.nbVarPos, nbData); %Reshape data for plotting
 
-% %% Iterative batch reconstruction (with recursive update of matrix inversion)
-% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-% disp('Iterative reconstruction');
-% [~,r(1).q] = max(GAMMA2,[],1); %works also for nbStates=1
-% r(1).MuQ = reshape(model.Mu(:,r(1).q), model.nbVar*T1, 1);
-% r(1).invSigmaQ = zeros(model.nbVar*T1);
-% for t=1:T1
-% 	idc = (t-1)*model.nbVar+1:t*model.nbVar;
-% 	r(1).invSigmaQ(idc,idc) = inv(model.Sigma(:,:,r(1).q(t)));
-% end
-% for t=1:T1
-% 	idc2 = (t-1)*model.nbVarPos+1:t*model.nbVarPos;
-% 	idc20 = 1:t*model.nbVarPos;
-% 	fprintf('.');
-% 	if t==1
-% 		invR = inv(A1(:,idc2)' * r(1).invSigmaQ * A1(:,idc2));
-% 	else
-% 		xrTmp = A1(:,idc20)' * r(1).invSigmaQ * A1(:,idc2);
-% 		invR = invUpdateSym(invR, xrTmp(1:end-model.nbVarPos,:), xrTmp(end-model.nbVarPos+1:end,:));
-% 	end
-% end
-% fprintf('\n');
-% rTmp = A1' * r(1).invSigmaQ * r(1).MuQ;
-% r(1).Data = reshape(invR*rTmp, model.nbVarPos, T1); %Reshape data for plotting
-
-
-% %% Iterative reconstruction (Tokuda, 1995) <- Not working yet
-% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-% disp('Iterative reconstruction');
-% [~,r(1).q] = max(GAMMA2,[],1); %works also for nbStates=1
-% r(1).MuQ = reshape(model.Mu(:,r(1).q), model.nbVar*T1, 1);
-% r(1).invSigmaQ = zeros(model.nbVar*T1);
-% for t=1:T1
-% 	idp = max(t-2,0)*model.nbVar+1:max(t-1,1)*model.nbVar;
-% 	idc = (t-1)*model.nbVar+1:t*model.nbVar;
-% 	r(1).invSigmaQ(idc,idc) = inv(model.Sigma(:,:,r(1).q(t)));
-% 	fprintf('.');
-% 	if t==1
-% % 		Ptmp = inv(A1(idc,:)' * r(1).invSigmaQ(idc,idc) * A1(idc,:));
-% % 		cTmp = Ptmp * (A1(idc,:)' * r(1).invSigmaQ(idc,idc) * r(1).MuQ(idc));
-% % 		Ptmp = zeros(model.nbVarPos*T1);
-% % 		cTmp = zeros(model.nbVarPos*T1,1);
-% 		Ptmp = inv(r(1).invSigmaQ(:,:));
-% 		cTmp = r(1).MuQ;
-% 	else
-% 		piTmp = Ptmp * A1(idc,:)';
-% 		nuTmp = A1(idc,:) * piTmp;
-% 		kTmp = piTmp / (eye(model.nbVar) + (r(1).invSigmaQ(idc,idc) - r(1).invSigmaQ(idp,idp)) * nuTmp);
-% 		cTmp = cTmp + kTmp * (r(1).invSigmaQ(idc,idc) * (r(1).MuQ(idc) - A1(idc,:)*cTmp) - r(1).invSigmaQ(idp,idp) * (r(1).MuQ(idp) - A1(idc,:)*cTmp));
-% 		Ptmp = Ptmp - kTmp * (r(1).invSigmaQ(idc,idc) - r(1).invSigmaQ(idp,idp)) * piTmp';
-% 	end
-% end
-% r(1).Data = reshape(cTmp, model.nbVarPos, T1); %Reshape data for plotting
-
-
-% %% Iterative reconstruction (Tokuda, 1995) <- Not working yet
-% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-% disp('Iterative reconstruction');
-% [~,r(1).q] = max(GAMMA2,[],1); %works also for nbStates=1
-% r(1).MuQ = reshape(model.Mu(:,r(1).q), model.nbVar*T1, 1);
-% r(1).invSigmaQ = zeros(model.nbVar*T1);
-% for t=1:T1
-% 	idp = max(t-2,0)*model.nbVar+1:max(t-1,1)*model.nbVar;
-% 	idc = (t-1)*model.nbVar+1:t*model.nbVar;
-% 	idc2 = (t-1)*model.nbVarPos+1:t*model.nbVarPos;
-% 	r(1).invSigmaQ(idc,idc) = inv(model.Sigma(:,:,r(1).q(t)));
-% 	fprintf('.');
-% 	if t==1
-% 		Rtmp = A1(idc,idc2)' * r(1).invSigmaQ(idc,idc) * A1(idc,idc2);
-%  		rTmp = A1(idc,idc2)' * r(1).invSigmaQ(idc,idc) * r(1).MuQ(idc);
-% 		%Rtmp = zeros(model.nbVarPos); %A1(idc,:)' * r(1).invSigmaQ(idc,idc) * A1(idc,:);
-%  		%rTmp = zeros(model.nbVarPos,1); %A1(idc,:)' * r(1).invSigmaQ(idc,idc) * r(1).MuQ(idc);
-% 		%Rtmp = inv(r(1).invSigmaQ(idc,idc));
-%  		%rTmp = r(1).MuQ(idc);
-% 	else
-% 		Dtmp = r(1).invSigmaQ(idc,idc) - r(1).invSigmaQ(idp,idp);
-% 		dTmp = r(1).invSigmaQ(idc,idc) * r(1).MuQ(idc) - r(1).invSigmaQ(idp,idp) * r(1).MuQ(idp);		
-% 		Rtmp = Rtmp + A1(idc,idc2)' * Dtmp * A1(idc,idc2);
-% 		rTmp = rTmp + A1(idc,idc2)' * dTmp; 
-% 	end
-% 	r(1).Data(:,t) = reshape(Rtmp\rTmp, model.nbVarPos, 1);
-% end
+%Rebuild covariance by reshaping S
+for t=1:nbData
+	id = (t-1)*model.nbVarPos+1:t*model.nbVarPos;
+	r(1).expSigma(:,:,t) = S(id,id) * nbData;
+end
 
 
 %% Plot 2D
@@ -209,12 +114,12 @@ end
 figure('position',[20,10,1200,600]);
 
 subplot(1,2,1); hold on;
-plotGMM(r(1).Data([1,2],:), r(1).expSigma([1,2],[1,2],:), [.5 .8 1]);
-plotGMM(model.Mu(1:2,:),model.Sigma(1:2,1:2,:),[.8 0 0]);
-% plotGMM(model.Mu(1:2,:),model.P(1:2,1:2,:),[1 .4 .4]);
-% for i=1:model.nbStates
-% 	plotGMM(model.Mu(1:2,i), model.L(1:2,:,i)*model.L(1:2,:,i)'+eye(2)*1E-1, [1 .4 .4]);
-% end
+plotGMM(r(1).Data([1,2],:), r(1).expSigma([1,2],[1,2],:), [.5 .8 1], .2);
+plotGMM(model.Mu(1:2,:),model.Sigma(1:2,1:2,:), [.8 0 0], .2);
+plotGMM(model.Mu(1:2,:),model.P(1:2,1:2,:), [1 .4 .4], .2);
+for i=1:model.nbStates
+	plotGMM(model.Mu(1:2,i), model.L(1:2,:,i)*model.L(1:2,:,i)'+eye(2)*1E-1, [1 .4 .4]);
+end
 plot(Data(1,:), Data(2,:),'.','linewidth',2,'color',[0,0,0]);
 plot(r(1).Data(1,:), r(1).Data(2,:),'-','linewidth',2,'color',[.8,0,0]);
 axis equal;
@@ -222,28 +127,16 @@ xlabel('x_1','fontsize',16); ylabel('x_2','fontsize',16);
 
 subplot(1,2,2); hold on;
 plotGMM(r(1).Data([3,4],:), r(1).expSigma([3,4],[3,4],:), [.5 .8 1]);
-plotGMM(model.Mu(3:4,:),model.Sigma(3:4,3:4,:),[.8 0 0]);
-% plotGMM(model.Mu(3:4,:),model.P(3:4,3:4,:),[1 .4 .4]);
-% for i=1:model.nbStates
-% 	plotGMM(model.Mu(3:4,i), model.L(3:4,:,i)*model.L(3:4,:,i)'+eye(2)*1E-1, [1 .4 .4]);
-% end
+plotGMM(model.Mu(3:4,:),model.Sigma(3:4,3:4,:), [.8 0 0], .2);
+plotGMM(model.Mu(3:4,:),model.P(3:4,3:4,:), [1 .4 .4], .2);
+for i=1:model.nbStates
+	plotGMM(model.Mu(3:4,i), model.L(3:4,:,i)*model.L(3:4,:,i)'+eye(2)*1E-1, [1 .4 .4]);
+end
 plot(Data(3,:), Data(4,:),'.','linewidth',2,'color',[0,0,0]);
 plot(r(1).Data(3,:), r(1).Data(4,:),'-','linewidth',2,'color',[.8,0,0]);
 axis equal;
 xlabel('x_3','fontsize',16); ylabel('x_4','fontsize',16);
 
 %print('-dpng','graphs/demo_trajMFA01.png');
-pause;
-close all;
-
-end
-
-%% Recursive update of matrix inversion fct
-%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-function M = invUpdateSym(A,x,r)
-	xA = x' * A;
-	q = eye(size(r)) / (r - xA * x);
-	Ax = A * x * q;
-	M = [A+Ax*xA, -Ax; -q*xA, q];
-end
-
+%pause;
+%close all;