demo_GMM02.m 7.74 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211
function demo_GMM02
% GMM with different covariance structures.
%
% 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{Calinon16JIST,
%   author="Calinon, S.",
%   title="A Tutorial on Task-Parameterized Movement Learning and Retrieval",
%   journal="Intelligent Service Robotics",
%		publisher="Springer Berlin Heidelberg",
%		doi="10.1007/s11370-015-0187-9",
%		year="2016",
%		volume="9",
%		number="1",
%		pages="1--29"
% }
% 
% 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
model.nbVar = 2; %Number of variables [x1,x2]
nbData = 100; %Length of each trajectory
nbSamples = 5; %Number of demonstrations

%Parameters of the EM algorithm
nbMinSteps = 50; %Minimum number of iterations allowed
nbMaxSteps = 200; %Maximum number of iterations allowed
maxDiffLL = 1E-5; %Likelihood increase threshold to stop the algorithm
diagRegularizationFactor = 1E-2; %Regularization term is optional


%% Load handwriting data
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
demos=[];
load('data/2Dletters/C.mat');
Data=[];
a=pi/3;
R = [cos(a) sin(a); -sin(a) cos(a)];
for n=1:nbSamples
	s(n).Data = spline(1:size(demos{n}.pos,2), demos{n}.pos, linspace(1,size(demos{n}.pos,2),nbData)); %Resampling
	Data = [Data, R*s(n).Data]; 
end

%Initialization
%model = init_GMM_kmeans(Data, model);
model = init_GMM_timeBased([repmat(1:nbData,1,nbSamples); Data], model);
model.Mu = model.Mu(2:end,:);
model.Sigma = model.Sigma(2:end,2:end,:);
nbData = nbData * nbSamples;


%% EM with isotropic covariances 
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
for nbIter=1:nbMaxSteps
	fprintf('.');
	%E-step
	[L, GAMMA] = computeGamma(Data, model); %See 'computeGamma' function below
	GAMMA2 = GAMMA ./ repmat(sum(GAMMA,2),1,nbData);
	%M-step
	for i=1:model.nbStates
		%Update Priors
		model.Priors(i) = sum(GAMMA(i,:)) / nbData;
		%Update Mu
		model.Mu(:,i) = Data * GAMMA2(i,:)';
		%Update Sigma
		DataTmp = Data - repmat(model.Mu(:,i),1,nbData);
		model.Sigma(:,:,i) = diag(diag(DataTmp * diag(GAMMA2(i,:)) * DataTmp')) + eye(size(Data,1)) * diagRegularizationFactor;
	end
	model.Sigma = repmat(eye(model.nbVar),[1 1 model.nbStates]) * mean(mean(mean(model.Sigma)));
	%Compute average log-likelihood
	LL(nbIter) = sum(log(sum(L,1))) / nbData;
	%Stop the algorithm if EM converged (small change of LL)
	if nbIter>nbMinSteps
		if LL(nbIter)-LL(nbIter-1)<maxDiffLL || nbIter==nbMaxSteps-1
			disp(['EM converged after ' num2str(nbIter) ' iterations.']);
			break;
		end
	end
end
disp(['The maximum number of ' num2str(nbMaxSteps) ' EM iterations has been reached.']);
m1 = model;


%% EM with diagonal covariances 
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
for nbIter=1:nbMaxSteps
	fprintf('.');
	%E-step
	[L, GAMMA] = computeGamma(Data, model); %See 'computeGamma' function below
	GAMMA2 = GAMMA ./ repmat(sum(GAMMA,2),1,nbData);
	%M-step
	for i=1:model.nbStates
		%Update Priors
		model.Priors(i) = sum(GAMMA(i,:)) / nbData;
		%Update Mu
		model.Mu(:,i) = Data * GAMMA2(i,:)';
		%Update Sigma
		DataTmp = Data - repmat(model.Mu(:,i),1,nbData);
		model.Sigma(:,:,i) = diag(diag(DataTmp * diag(GAMMA2(i,:)) * DataTmp')) + eye(size(Data,1)) * diagRegularizationFactor;
	end
	%Compute average log-likelihood
	LL(nbIter) = sum(log(sum(L,1))) / nbData;
	%Stop the algorithm if EM converged (small change of LL)
	if nbIter>nbMinSteps
		if LL(nbIter)-LL(nbIter-1)<maxDiffLL || nbIter==nbMaxSteps-1
			disp(['EM converged after ' num2str(nbIter) ' iterations.']);
			break;
		end
	end
end
disp(['The maximum number of ' num2str(nbMaxSteps) ' EM iterations has been reached.']);
m2 = model;


%% EM for full covariance matrices
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
[m3,~,LL] = EM_GMM(Data, model);


%% EM with tied covariances 
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
for nbIter=1:nbMaxSteps
	fprintf('.');
	%E-step
	[L, GAMMA] = computeGamma(Data, model); %See 'computeGamma' function below
	GAMMA2 = GAMMA ./ repmat(sum(GAMMA,2),1,nbData);
	%M-step
	for i=1:model.nbStates
		%Update Priors
		model.Priors(i) = sum(GAMMA(i,:)) / nbData;
		%Update Mu
		model.Mu(:,i) = Data * GAMMA2(i,:)';
		%Update Sigma
		DataTmp = Data - repmat(model.Mu(:,i),1,nbData);
		model.Sigma(:,:,i) = DataTmp * diag(GAMMA2(i,:)) * DataTmp' + eye(size(Data,1)) * diagRegularizationFactor;
	end
	model.Sigma = repmat(mean(model.Sigma,3), [1 1 model.nbStates]);
	%Compute average log-likelihood
	LL(nbIter) = sum(log(sum(L,1))) / nbData;
	%Stop the algorithm if EM converged (small change of LL)
	if nbIter>nbMinSteps
		if LL(nbIter)-LL(nbIter-1)<maxDiffLL || nbIter==nbMaxSteps-1
			disp(['EM converged after ' num2str(nbIter) ' iterations.']);
			break;
		end
	end
end
disp(['The maximum number of ' num2str(nbMaxSteps) ' EM iterations has been reached.']);
m4 = model;


%% Plots
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
figure('PaperPosition',[0 0 16 5],'position',[10,10,1300,400]); 
%Isotropic covariance
subplot(1,4,1); hold on; axis off; title('Isotropic','fontsize',14);
plotGMM(m1.Mu, m1.Sigma, [.8 0 0], .5);
plot(Data(1,:),Data(2,:),'.','markersize',12,'color',[.5 .5 .5]);
axis([min(Data(1,:))-1E0 max(Data(1,:))+1E0 min(Data(2,:))-1E0 max(Data(2,:))+1E0]); axis equal; 
%Diagonal covariance
subplot(1,4,2); hold on; axis off; title('Diagonal','fontsize',14);
plotGMM(m2.Mu, m2.Sigma, [.8 0 0], .5);
plot(Data(1,:),Data(2,:),'.','markersize',12,'color',[.5 .5 .5]);
axis([min(Data(1,:))-1E0 max(Data(1,:))+1E0 min(Data(2,:))-1E0 max(Data(2,:))+1E0]); axis equal; 
%Full covariance
subplot(1,4,3); hold on; axis off; title('Full','fontsize',14);
plotGMM(m3.Mu, m3.Sigma, [.8 0 0], .5);
plot(Data(1,:),Data(2,:),'.','markersize',12,'color',[.5 .5 .5]);
axis([min(Data(1,:))-1E0 max(Data(1,:))+1E0 min(Data(2,:))-1E0 max(Data(2,:))+1E0]); axis equal; 
%Tied covariance
subplot(1,4,4); hold on; axis off; title('Tied','fontsize',14);
plotGMM(m4.Mu, m4.Sigma, [.8 0 0], .5);
plot(Data(1,:),Data(2,:),'.','markersize',12,'color',[.5 .5 .5]);
axis([min(Data(1,:))-1E0 max(Data(1,:))+1E0 min(Data(2,:))-1E0 max(Data(2,:))+1E0]); axis equal;

%print('-dpng','graphs/demo_GMM02.png');
%pause;
%close all;
end

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
function [L, GAMMA] = computeGamma(Data, model)
L = zeros(model.nbStates,size(Data,2));
for i=1:model.nbStates
	L(i,:) = model.Priors(i) * gaussPDF(Data, model.Mu(:,i), model.Sigma(:,:,i));
end
GAMMA = L ./ repmat(sum(L,1)+realmin, model.nbStates, 1);
end