P_EKFPURPOSEConstructor for Extended Kalman Filter for PoseSLAM.
SYNOPSISfunction EKF=P_EKF(varargin)
DESCRIPTIONConstructor for Extended Kalman Filter for PoseSLAM. This is a sub-type of Pose SLAM filter (P_Filter), and thus it inherits all methods from the P_Filter. This type of filter estimates the robot's trajectory representing it as Gaussian represented in the usual mean and covariance form. The possible parameters are - Another 'P_EKF'. Copy constructor. - A Gaussian given the initial estimation. Generates a new 'Extended Kalman Filter'. See also P_Filter, P_TRO. CROSS-REFERENCE INFORMATIONThis function calls:
SOURCE CODE0001 function EKF=P_EKF(varargin) 0002 % Constructor for Extended Kalman Filter for PoseSLAM. 0003 % 0004 % This is a sub-type of Pose SLAM filter (P_Filter), and thus it 0005 % inherits all methods from the P_Filter. 0006 % 0007 % This type of filter estimates the robot's trajectory representing it as 0008 % Gaussian represented in the usual mean and covariance form. 0009 % 0010 % The possible parameters are 0011 % - Another 'P_EKF'. Copy constructor. 0012 % - A Gaussian given the initial estimation. Generates a new 'Extended 0013 % Kalman Filter'. 0014 % 0015 % See also P_Filter, P_TRO. 0016 0017 switch nargin 0018 case 1 0019 if isa(varargin{1},'P_EKF') 0020 EKF=varargin{1}; 0021 else 0022 if isa(varargin{1},'Gaussian') 0023 F=P_Filter(varargin{1}); 0024 0025 EKF.mu=get(varargin{1},'mean'); 0026 EKF.Sigma=get(varargin{1},'covariance'); 0027 0028 EKF=class(EKF,'P_EKF',F); 0029 else 0030 error('Wrong parameter type in P_EKF creation'); 0031 end 0032 end 0033 otherwise 0034 error('Wrong number of parameters in P_EKF creation'); 0035 end |