ROOT logo
HYDRA - THE HADES ANALYSIS PACKAGE » (UNKNOWN) » HKalIFilt

class HKalIFilt: public TObject

_HADES_CLASS_DESCRIPTION


 This class is responsible for the Kalman filter.

 The Kalman filter is started via the
 Bool_t fitTrack(const TObjArray &hits,  const TVectorD &iniStateVec,
                 const TMatrixD &iniCovMat)
 function. It needs a series of measurement points (an array of class
 HKalMdcHit) and initial estimations for the track state and covariance
 matrix as input.

 It will then make an estimation for the initial track state based on the
 measurement hits and fill the covariance matrix with large values.
 The function will return a boolean to indicate whether problems (high chi^2
 or unrealistic track parameters) were encountered during track fitting.

 Track propagation will be done with the Runge-Kutta method.

 After the Kalman filter is done, a measurement site may be eliminated
 from the calculation with the function
 excludeSite(Int_t iSite)


 Several options for the Kalman filter may be set:
 setNumIterations(Int_t kalRuns)
 Number of iterations. After each iteration the Kalman filter will use the
 result of the previous iteration as starting value.
 Default is 1.

 setDirection(Bool_t dir)
 Propagation direction (kIterForward, kIterBackward). Direction will switch
 after each iteration.
 Default is forward direction.

 setSmoothing(Bool_t smooth)
 Smooth or don't smooth track states after filter. Smoothing attempts to
 improve the filtered track states by using the results of all subsequent
 as well.
 Default is on.

 setRotation(Kalman::kalRotateOptions rotate)
 kNoRot: No coordinate transformation. Not recommended for high track angles
         (> 30°).
 kVarRot (default): Tilt the coordinate system along the initial track
                    direction to avoid large values for the track state
                    parameters tx or ty.

 setDoEnerLoss(Bool_t dedx)
 setDoMultScat(Bool_t ms)
 Include energy or multiple scattering in the Kalman filter.
 Default is on.

 setConstField(Bool_t constField)
 setFieldVector(const TVector3 &B)
 Tells the Kalman filter to use a constant magnetic field instead of the
 field map.
 Field vector must be in Tesla.
 Default is off.

 setFilterMethod(Kalman::filtMethod type)
 Changes which formulation of the Kalman equations to use. The formulations
 differ in speed and numerical stability. See the description of the
 functions named filter... for details.

 Notation:
 a: track state vector
 m: measurement vector
 r: residual of the measurement vector and the predicted measurement
 f(a): propagation function: Propagate track state a to the next
       detector.
 h(a): projection function that calculates a measurement vector from
       track state v
 F: Jacobian of f(a)
 H: Jacobian of h(a)
 C: covariance matrix of the track state
 Q: covariance matrix of the process noise
 V: covariance matrix of the measurement errors



Function Members (Methods)

 
    This is an abstract class, constructors will not be documented.
    Look at the header to check for available constructors.

public:
virtual~HKalIFilt()
voidTObject::AbstractMethod(const char* method) const
virtual voidTObject::AppendPad(Option_t* option = "")
virtual voidTObject::Browse(TBrowser* b)
virtual Bool_tcalcMeasVecFromState(TVectorD& projMeasVec, const HKalTrackSite *const site, Kalman::kalFilterTypes stateType, Kalman::coordSys sys) const
virtual Bool_tcheckCovMat(const TMatrixD& fCov) const
static TClass*Class()
virtual const char*TObject::ClassName() const
virtual voidTObject::Clear(Option_t* = "")
virtual TObject*TObject::Clone(const char* newname = "") const
virtual Int_tTObject::Compare(const TObject* obj) const
virtual voidTObject::Copy(TObject& object) const
virtual voidTObject::Delete(Option_t* option = "")MENU
virtual Int_tTObject::DistancetoPrimitive(Int_t px, Int_t py)
virtual voidTObject::Draw(Option_t* option = "")
virtual voidTObject::DrawClass() constMENU
virtual TObject*TObject::DrawClone(Option_t* option = "") constMENU
virtual voidTObject::Dump() constMENU
virtual voidTObject::Error(const char* method, const char* msgfmt) const
virtual Bool_texcludeSite(Int_t iSite)
virtual voidTObject::Execute(const char* method, const char* params, Int_t* error = 0)
virtual voidTObject::Execute(TMethod* method, TObjArray* params, Int_t* error = 0)
virtual voidTObject::ExecuteEvent(Int_t event, Int_t px, Int_t py)
virtual voidTObject::Fatal(const char* method, const char* msgfmt) const
virtual Bool_tfilter(Int_t iSite)
virtual TObject*TObject::FindObject(const char* name) const
virtual TObject*TObject::FindObject(const TObject* obj) const
virtual Bool_tfitTrack(const TObjArray& hits, const TVectorD& iniStateVec, const TMatrixD& iniCovMat, Int_t pId)
virtual Double_tgetBetaInput() const
virtual Double_tgetChi2() const
virtual voidgetCovErrs(Int_t& nSymErrs, Int_t& nPosDefErrs) const
virtual Double_tgetDafChi2Cut() const
virtual const Double_t*getDafT() const
virtual Bool_tgetDirection() const
virtual Bool_tgetDoDaf() const
virtual Bool_tgetDoEnerLoss() const
virtual Bool_tgetDoMultScat() const
virtual Bool_tgetDoSmooth() const
virtual Option_t*TObject::GetDrawOption() const
static Long_tTObject::GetDtorOnly()
virtual Double_tgetFieldIntegral() const
virtual const TObjArray&getFieldTrack() const
virtual Int_tgetFilterMethod() const
virtual const TMatrixD&getHitErrMat(HKalTrackSite *const site) const
virtual Int_tgetHitType() const
virtual const TVectorD&getHitVec(HKalTrackSite *const site) const
virtual const char*TObject::GetIconName() const
virtual const TVectorD&getIniStateVec() const
virtual Bool_tgetLastTrackAccepted() const
virtual Int_tgetMeasDim() const
virtual voidgetMetaPos(Double_t& x, Double_t& y, Double_t& z) const
virtual const char*TObject::GetName() const
virtual Int_tgetNdafs() const
virtual Double_tgetNdf() const
virtual Int_tgetNhits() const
virtual Int_tgetNiter() const
virtual Int_tgetNmaxSites() const
virtual Int_tgetNsites() const
virtual char*TObject::GetObjectInfo(Int_t px, Int_t py) const
static Bool_tTObject::GetObjectStat()
virtual Option_t*TObject::GetOption() const
virtual Int_tgetPid() const
virtual const TObjArray&getPointsTrack() const
virtual Bool_tgetPrintErr() const
virtual Bool_tgetPrintWarn() const
virtual Int_tgetRotation() const
virtual HKalTrackSite*getSite(UInt_t site) const
virtual Int_tgetStateDim(Kalman::coordSys coord = kSecCoord) const
virtual const char*TObject::GetTitle() const
virtual Double_tgetTrackLength() const
virtual Int_tgetTrackNum() const
virtual const HKalRungeKutta*getTrackPropagator() const
virtual UInt_tTObject::GetUniqueID() const
virtual voidgetVertexPos(Double_t& x, Double_t& y, Double_t& z) const
virtual Bool_tTObject::HandleTimer(TTimer* timer)
virtual ULong_tTObject::Hash() const
virtual voidTObject::Info(const char* method, const char* msgfmt) const
virtual Bool_tTObject::InheritsFrom(const char* classname) const
virtual Bool_tTObject::InheritsFrom(const TClass* cl) const
virtual voidTObject::Inspect() constMENU
voidTObject::InvertBit(UInt_t f)
virtual TClass*IsA() const
virtual Bool_tTObject::IsEqual(const TObject* obj) const
virtual Bool_tTObject::IsFolder() const
Bool_tTObject::IsOnHeap() const
virtual Bool_tTObject::IsSortable() const
Bool_tTObject::IsZombie() const
virtual voidTObject::ls(Option_t* option = "") const
voidTObject::MayNotUse(const char* method) const
virtual Bool_tTObject::Notify()
voidTObject::Obsolete(const char* method, const char* asOfVers, const char* removedFromVers) const
static voidTObject::operator delete(void* ptr)
static voidTObject::operator delete(void* ptr, void* vp)
static voidTObject::operator delete[](void* ptr)
static voidTObject::operator delete[](void* ptr, void* vp)
void*TObject::operator new(size_t sz)
void*TObject::operator new(size_t sz, void* vp)
void*TObject::operator new[](size_t sz)
void*TObject::operator new[](size_t sz, void* vp)
TObject&TObject::operator=(const TObject& rhs)
virtual voidTObject::Paint(Option_t* option = "")
virtual voidTObject::Pop()
virtual voidTObject::Print(Option_t* option = "") const
virtual Bool_tpropagate(Int_t iFromSite, Int_t iToSite)
virtual Bool_tpropagateToPlane(TVectorD& svTo, const TVectorD& svFrom, const HKalMdcMeasLayer& measLayFrom, const HKalMdcMeasLayer& measLayTo, Int_t pid, Bool_t dir)
virtual Int_tTObject::Read(const char* name)
virtual voidTObject::RecursiveRemove(TObject* obj)
voidTObject::ResetBit(UInt_t f)
virtual Bool_trunFilter(Int_t fromSite, Int_t toSite)
virtual voidTObject::SaveAs(const char* filename = "", Option_t* option = "") constMENU
virtual voidTObject::SavePrimitive(ostream& out, Option_t* option = "")
virtual voidsetBetaInput(Double_t b)
voidTObject::SetBit(UInt_t f)
voidTObject::SetBit(UInt_t f, Bool_t set)
virtual voidsetConstField(Bool_t constField)
virtual voidsetDafPars(Double_t chi2cut, const Double_t* T, Int_t n)
virtual voidsetDirection(Bool_t dir)
virtual voidsetDoEnerLoss(Bool_t dedx)
virtual voidsetDoMultScat(Bool_t ms)
virtual voidTObject::SetDrawOption(Option_t* option = "")MENU
static voidTObject::SetDtorOnly(void* obj)
virtual voidsetFieldMap(HMdcTrackGField* fMap, Double_t fpol)
virtual voidsetFieldVector(const TVector3& B)
virtual voidsetFillPointsArrays(Bool_t fill)
virtual voidsetFilterMethod(Kalman::filtMethod type)
virtual voidsetHitType(Kalman::kalHitTypes hType)
virtual voidsetNumIterations(Int_t kalRuns)
static voidTObject::SetObjectStat(Bool_t stat)
virtual voidsetPrintErrors(Bool_t print)
virtual voidsetPrintWarnings(Bool_t print)
virtual voidsetRotation(Kalman::kalRotateOptions rotate)
virtual voidsetRotationAngles(Double_t rotXAngle, Double_t rotYAngle)
virtual voidsetRungeKuttaParams(Float_t initialStpSize, Float_t stpSizeDec, Float_t stpSizeInc, Float_t maxStpSize, Float_t minStpSize, Float_t minPrec, Float_t maxPrec, Int_t maxNumStps, Int_t maxNumStpsPCA, Float_t maxDst, Double_t minLngthCalcQ)
virtual voidsetSmoothing(Bool_t smooth)
virtual voidTObject::SetUniqueID(UInt_t uid)
virtual voidShowMembers(TMemberInspector&)
virtual Bool_tsmooth()
virtual voidsortHits()
virtual voidStreamer(TBuffer&)
voidStreamerNVirtual(TBuffer& ClassDef_StreamerNVirtual_b)
virtual voidTObject::SysError(const char* method, const char* msgfmt) const
Bool_tTObject::TestBit(UInt_t f) const
Int_tTObject::TestBits(UInt_t f) const
virtual Bool_ttraceToMeta(const TVector3& metaHit, const TVector3& metaNormVec)
virtual Bool_ttraceToVertex()
virtual voidtransformFromSectorToTrack()
virtual voidtransformFromTrackToSector()
virtual voidupdateSites(const TObjArray& hits)
virtual voidTObject::UseCurrentStyle()
virtual voidTObject::Warning(const char* method, const char* msgfmt) const
virtual Int_tTObject::Write(const char* name = 0, Int_t option = 0, Int_t bufsize = 0)
virtual Int_tTObject::Write(const char* name = 0, Int_t option = 0, Int_t bufsize = 0) const
protected:
virtual Bool_tcalcProjector(Int_t iSite) const
virtual Bool_tcheckSitePreFilter(Int_t iSite) const
virtual voidTObject::DoError(int level, const char* location, const char* fmt, va_list va) const
virtual voidfilterConventional(Int_t iSite)
virtual voidfilterJoseph(Int_t iSite)
virtual voidfilterSequential(Int_t iSite)
virtual voidfilterSwerling(Int_t iSite)
virtual voidfilterUD(Int_t iSite)
virtual Kalman::coordSysgetFilterInCoordSys() const
virtual TRotation*getRotMat() const
voidTObject::MakeZombie()
virtual voidnewTrack(const TObjArray& hits, const TVectorD& iniSv, const TMatrixD& iniCovMat, Int_t pid)
virtual voidpropagateCovConv(Int_t iFromSite, Int_t iToSite)
virtual voidpropagateCovUD(Int_t iFromSite, Int_t iToSite)
virtual Bool_tpropagateTrack(Int_t iFromSite, Int_t iToSite)
virtual voidsetChi2(Double_t c)
virtual voidsetNHitsInTrack(Int_t n)
virtual voidsetNSites(Int_t n)
virtual voidsetTrackChi2(Double_t c)
virtual voidsetTrackLength(Double_t l)
virtual voidsetTrackLengthAtLastMdc(Double_t l)
virtual voidupdateChi2Filter(Int_t iSite)

Data Members

private:
Bool_tbDoDEDXEnergy loss.
Bool_tbDoMSMultiple scattering.
Bool_tbDoSmooth! Do smoothing.
Bool_tbFillPointArrays== kTRUE if point arrays should be filled
Bool_tbPrintErr! Print error messages.
Bool_tbPrintWarn! Print warning messages.
Bool_tbTrackAcceptedTrack filtering done without errors.
Double_tbetaInputBeta value used for initial particle hypothesis.
Double_tchi2chi2 of track. Will be -1 if fit failed.
Bool_tdirectionPropagation direction: kIterForward/kIterBackward
TObjArrayfieldTrackField from Runge-Kutta stepping at Points along trajectory stored
Int_tfiltTypeSwitch between alternate formulations of the Kalman equations.
Int_thitTypeWire or segment hits.
TVectorDiniStateVecEstimation of the track state vector at the first measurement site.
Int_tnCondErrsNumber of times when a matrix was ill-conditioned for inversion. Only filled if kalDebug > 0.
Int_tnCovPosDefErrsNumber of times the covariance matrix was not positive definite. Only filled if kalDebug > 0.
Int_tnCovSymErrsNumber of symmetry breaking in the covariance matrix. Only filled if kalDebug > 0.
Int_tnHitsInTrackNumber of sites in current track.
Int_tnKalRunsNumber of Kalman filter iterations.
Int_tnMaxSitesMaximum number of sites that can be stored.
Int_tnSitesNumber of measurement sites in track.
TRotation*pRotMat! Rotation matrix for possible coordinate tilting.
TVector3*pTransVec! Translation vector for possible coordinate transformations.
Int_tpidGeant particle id.
TObjArraypointsTrackPoints from Runge-Kutta stepping along trajectory stored
TVector3posMeta! Position information at meta detector.
TVector3posVertex! Position information at vertex.
Int_trotCoordsOption to tilt coordinate system for track fitting.
HKalTrackSite**sites! Array of MDC track sites.
TVectorDsvMeta! Track state at META detector.
TVectorDsvVertex! Track state at vertex.
Double_ttrackLengthTrack length from target.
Double_ttrackLengthAtLastMdcTrack length from target to last MDC.
Int_ttrackNumNumber of tracks fitted.
HKalRungeKuttatrackPropagator! The object that realizes the track propagation.

Class Charts

Inheritance Inherited Members Includes Libraries
Class Charts

Function documentation

~HKalIFilt()
Bool_t checkSitePreFilter(Int_t iSite) const
 Checks for potential issues when site with index iSite is filtered.
void filterConventional(Int_t iSite)
 Filter a site using the conventional formulation of the Kalman filter
 equations.

 C_k = (I - K_k * H_k) * C^{k-1}_k
 K_k = C^{k-1}_k * H^T_k * (V_k + H_k * C^{k-1}_k * H^T_k)^-1

 These are simpler equations compared to the Joseph or Swerling
 forumations. Only one inversion of a matrix with the dimension of the
 measurement vector is neccessary. However, the updated covariance
 matrix may not be positive definite due to numerical computing problems.
void filterJoseph(Int_t iSite)
 This filter method uses the Joseph stabilized update of the covariance
 matrix.

 K_k = C^k-1_k * H^T * (V_k + H_k * C^k-1_k * H_k^T)^-1
 C^k = (I - K_k * H) * C^k-1_k * (I - K_k * H)^T + K_k * V_k * K_k^T

 This method is numerically more stable than the conventional or
 Swerling formulations of the Kalman equations.
 It guarantees that the updated covariance matrix is positive definite
 if the covariance from the prediction step and the measurement noise
 covariance are also positive definite.
void filterSequential(Int_t iSite)
 Implements the sequential Kalman filter..
 May only be used if:
 the measurement noise matrix is diagonal or it is constant
 and the projection function is h(a) = H * a.

 The advantage of this method is that is avoids matrix inversions.
void filterSwerling(Int_t iSite)
 Swerling calculation of covariance matrix for filtered state and the
 Kalman gain matrix.

 C_k = [ (C^k-1_k)^-1 + H^T_k * (V_k)^-1 * H_k ]^-1
 K_k = C_k * H^T_k * (V_k)^-1

 This form requires two inversions of matrices with the dimension of the
 state vector and one inversion of a matrix with the dimension of the
 measurement vector. It can be more efficient if the dimension of the
 state vector is small.
void filterUD(Int_t iSite)
 Update of the covariance matrix and state vector for the filter step
 using the U-D filter. A UD decomposition of the covariance matrix
 is used and only the U and D matrices are propagated.

 This method increases the numerical precision of the Kalman filter.
 It cannot be used together with the annealing filter.

 Literature:
 Optimal State Estimation: Kalman, H infinity and Nonlinear Approaches
 Chapter 6.4: U-D filtering
 Dan Simon

 Kalman Filtering: Theory and Practice using MATLAB, 3rd edition
 Chapter 6.5: Square Root and UD Filters
 Mohinder S. Grewal, Angus P. Andrews

 G. J. Bierman, Factorization Methods for Discrete Sequential Estimation,
 Academic Press, New York 1977
void propagateCovConv(Int_t iFromSite, Int_t iToSite)
 Propagate the covariance matrix between measurement sites.
 Must not be called before propagateTrack().
 When applying the UD filter use propagateCovUD() function instead.

 iFromSite:  index of measurement site to start propagation from.
 iToSite:    index of measurement site to propagate to (will be modified).
void propagateCovUD(Int_t iFromSite, Int_t iToSite)
 Update of the covariance matrix' U and D factors after the prediction
 step.

 iFromSite:  index of measurement site to start propagation from.
 iToSite:    index of measurement site to propagate to (will be modified).

 Only the matrix upper triangular U with the elements of D on its
 diagonal are stored in the site.

 Literature:
 Kalman Filtering: Theory and Practice using MATLAB, 3rd edition
 Chapter 6.5: Square Root and UD Filters
 Mohinder S. Grewal, Angus P. Andrews
 and
 Catherine L. Thornton, Triangular covariance factorizations for Kalman filtering,
 Ph.D. thesis, University of California at Los Angeles, 1976
Bool_t propagateTrack(Int_t iFromSite, Int_t iToSite)
 Propagates the track between measurement sites.

 iFromSite:  index of measurement site to start propagation from.
 iToSite:    index of measurement site to propagate to (will be modified).
void updateChi2Filter(Int_t iSite)
 Update chi^2 after having filtered site number iSite.
void newTrack(const TObjArray& hits, const TVectorD& iniSv, const TMatrixD& iniCovMat, Int_t pid)
 Reset data members to fit a new track.

 Input:
 hits:        the array with the measurement hits. Elements must be of
              class HKalMdcHit.
 iniStateVec: initial track state that the filter will use.
 iniCovMat:   initial covariance matrix that the filter will use.
 pId:         Geant particle id.
 momGeant:    Geant momentum that will be written in the output tree.
              Ignore if this is not simulation data.
Bool_t calcMeasVecFromState(TVectorD& projMeasVec, const HKalTrackSite *const site, Kalman::kalFilterTypes stateType, Kalman::coordSys sys) const
 Implements the projection function h(a) that calculates a measurement
 vector from a track state.

 Output:
 projMeasVec: The calculated measurement vector.
 Input:
 site:      Pointer to current site of the track.
 stateType: Which state (predicted, filtered, smoothed) to project on a
            measurement vector.
 sys:       Coordinate system to use (sector or virtual layer coordinates)
Bool_t checkCovMat(const TMatrixD& fCov) const
 Covariance matrices must be positive definite, i.e. symmetric and
 all its eigenvalues are real and positive. Returns true if this
 is the case.
Bool_t excludeSite(Int_t iSite)
 Exclude a site from the measurement. Requires that prediction, filtering and smoothing
 has been done before. If smoothing has been disabled it will be done in this function.
 iSite: index in sites array of the site to exclude
Bool_t filter(Int_t iSite)
 Run the filter step in Kalman filter for a site.
 Must be called after the prediction step.
 Different Kalman filter equations are used as set by setFilterMethod().
 iSite: index of site to filter
Bool_t fitTrack(const TObjArray& hits, const TVectorD& iniStateVec, const TMatrixD& iniCovMat, Int_t pId)
 Runs the Kalman filter over a set of measurement hits.
 Returns false if the Kalman filter encountered problems during
 track fitting or the chi^2 is too high.

 Input:
 hits:        the array with the measurement hits. Elements must be of
              class HKalMdcHit.
 iniStateVec: initial track state that the filter will use.
 iniCovMat:   initial covariance matrix that the filter will use.
 pId:         Geant particle id.
 momGeant:    Geant momentum that will be written in the output tree.
              Ignore if this is not simulation data.
Bool_t propagate(Int_t iFromSite, Int_t iToSite)
 Propagates the track to the next measurement site and update
 covariance matrices.

 iFromSite:  index of measurement site to start propagation from.
 iToSite:    index of measurement site to propagate to.
Bool_t propagateToPlane(TVectorD& svTo, const TVectorD& svFrom, const HKalMdcMeasLayer& measLayFrom, const HKalMdcMeasLayer& measLayTo, Int_t pid, Bool_t dir)
Bool_t runFilter(Int_t fromSite, Int_t toSite)
 Do the prediction and filter steps of the Kalman filter by propagating
 the track between the measurement sites iFromSite and toSite.

 iFromSite: index of track site to start propagation from
 toSite:   index of track site to propagate to.
Bool_t smooth()
 Implements the smoother by Rauch, Tung and Striebel for the Kalman filter.
 Requires that the prediction and filter steps for all measurement
 sites have been executed before.
void sortHits()
 Sort the competitors in each site by weight.
Bool_t traceToVertex()
Bool_t traceToMeta(const TVector3& metaHit, const TVector3& metaNormVec)
 Propagates the track from the last fitted MDC position till track intersection
 with META plane (is defined by META-hit and normal vector to rod's plane.
 Should only be called after having filtered all sites.

 Input:
 metaHit:
 metaNormVec:
void transformFromSectorToTrack()
 Transform all sites using the Kalman system's rotation matrix.
void transformFromTrackToSector()
 Transform all sites using the inverse rotation matrix stored in the
 Kalman system. This will transform the sites back to sector coordinates
 after a call of transformFromSectorToTrack() and if the rotation matrix
 has not been modified in the meantime.
void updateSites(const TObjArray& hits)
 Replace sites of the Kalman system with new hits.
 hits: array with new measurement hits. Must be of class HKalMdcHit.
TMatrixD const& getHitErrMat(HKalTrackSite *const site) const
 Returns the measurement error of site.

 Input:
 site: measurement site.
TVectorD const& getHitVec(HKalTrackSite *const site) const
 Returns the measurement vector of measurement site.

 Input:
 site: measurement site.
void getMetaPos(Double_t& x, Double_t& y, Double_t& z) const
void getVertexPos(Double_t& x, Double_t& y, Double_t& z) const
Double_t getNdf() const
 Returns number degrees of freedom, i.e. number of experimental points
 minus number of parameters that are estimated.
void setPrintErrors(Bool_t print)
 Print or suppress error messages.
void setPrintWarnings(Bool_t print)
 Print or suppress warning messages.
void setRotation(Kalman::kalRotateOptions rotate)
 Set options for the Kalman filter.
 kalRotateOptions: Tilt coordinate system.
 There are (approximately) three options:
 1. kNoRot:
    Don't tilt the coordinate system.
 2. kVarRot:
    Tilt the coordinate system so that the z-axis will always
    point in the initial track direction. Assuming track curvature
    is not large this ensures that the track state parameters
    tx = tan(p_x / p_z) and ty = tan(p_y / p_z) remain small.
    Angles close to 90° would result in large values for tx and ty
    due to the tangens and poor results for the Kalman filter.
void setRotationAngles(Double_t rotXAngle, Double_t rotYAngle)
 Set the rotation matrix.
 rotXangle: rotation angle around x axis in radians.
 rotYangle: rotation angle around y axis in radians.
Bool_t calcProjector(Int_t iSite) const
Kalman::coordSys getFilterInCoordSys() const
{ return Kalman::kSecCoord; }
TRotation* getRotMat() const
{ return pRotMat; }
void setChi2(Double_t c)
{ chi2 = c; }
void setNSites(Int_t n)
{ nSites = n; }
void setNHitsInTrack(Int_t n)
{ nHitsInTrack = n; }
void setTrackChi2(Double_t c)
{ chi2 = c; }
void setTrackLength(Double_t l)
{ trackLength = l; }
void setTrackLengthAtLastMdc(Double_t l)
Double_t getBetaInput() const
{ return betaInput; }
Double_t getChi2() const
{ return chi2; }
void getCovErrs(Int_t& nSymErrs, Int_t& nPosDefErrs) const
{ nSymErrs = nCovSymErrs; nPosDefErrs = nCovPosDefErrs; }
Double_t getDafChi2Cut() const
{ return -1.; }
const Double_t* getDafT() const
{ return NULL; }
Bool_t getDirection() const
{ return direction; }
Bool_t getDoDaf() const
{ return kFALSE; }
Bool_t getDoEnerLoss() const
{ return bDoDEDX; }
Bool_t getDoMultScat() const
{ return bDoMS; }
Bool_t getDoSmooth() const
{ return bDoSmooth; }
Double_t getFieldIntegral() const
Int_t getFilterMethod() const
{ return filtType; }
TVectorD const& getIniStateVec() const
{ return iniStateVec; }
TObjArray const& getFieldTrack() const
{ return fieldTrack; }
Int_t getHitType() const
{ return hitType; }
Bool_t getLastTrackAccepted() const
{ return bTrackAccepted; }
Int_t getMeasDim() const
{ return getSite(0)->getMeasDim(); }
Int_t getNdafs() const
{ return 0; }
Int_t getNhits() const
{ return nHitsInTrack; }
Int_t getNiter() const
{ return nKalRuns; }
Int_t getNmaxSites() const
{ return nMaxSites; }
Int_t getNsites() const
{ return nSites; }
Int_t getPid() const
{ return pid; }
TObjArray const& getPointsTrack() const
{ return pointsTrack; }
const HKalRungeKutta* getTrackPropagator() const
{ return &trackPropagator; }
HKalTrackSite* getSite(UInt_t site) const
Bool_t getPrintErr() const
{ return bPrintErr; }
Bool_t getPrintWarn() const
{ return bPrintWarn; }
Int_t getRotation() const
{ return rotCoords; }
Int_t getStateDim(Kalman::coordSys coord = kSecCoord) const
{ return getSite(0)->getStateDim(coord); }
Double_t getTrackLength() const
{ return trackLength; }
Int_t getTrackNum() const
{ return trackNum; }
void setBetaInput(Double_t b)
{ betaInput = b; }
void setConstField(Bool_t constField)
void setDafPars(Double_t chi2cut, const Double_t* T, Int_t n)
{ ; }
void setDirection(Bool_t dir)
void setDoEnerLoss(Bool_t dedx)
void setDoMultScat(Bool_t ms)
void setFillPointsArrays(Bool_t fill)
void setFieldMap(HMdcTrackGField* fMap, Double_t fpol)
{ trackPropagator.setFieldMap(fMap, fpol); }
void setFieldVector(const TVector3& B)
void setFilterMethod(Kalman::filtMethod type)
{ filtType = type; }
void setHitType(Kalman::kalHitTypes hType)
{ hitType = hType; }
void setNumIterations(Int_t kalRuns)
{ nKalRuns = kalRuns; }
void setRungeKuttaParams(Float_t initialStpSize, Float_t stpSizeDec, Float_t stpSizeInc, Float_t maxStpSize, Float_t minStpSize, Float_t minPrec, Float_t maxPrec, Int_t maxNumStps, Int_t maxNumStpsPCA, Float_t maxDst, Double_t minLngthCalcQ)