TooN Algorithm Library - tag  0.2
Namespaces | Classes | Typedefs | Functions | Variables
tag Namespace Reference

Namespaces

namespace  ConstantPosition
 
namespace  ConstantVelocity
 
namespace  Internal
 

Classes

class  array
 
struct  array< int,-1 >
 
struct  mem_data_ref_t
 
struct  const_mem_data_ref_t
 
struct  mem_data_t
 
struct  const_mem_data_t
 
struct  bind_t
 
struct  member_iterator_t
 
struct  Point4SE3Estimation
 
class  KalmanFilter
 
class  IncrementalPose
 
class  WorldPose
 
class  WorldPosition
 
class  AngularVelocity
 
class  WorldDirection
 
struct  Homography
 
struct  AffineHomography
 
struct  CameraRotation
 
struct  PlaneFromPoints
 
struct  T_list
 
struct  V_list
 
struct  V_tuple
 

Typedefs

typedef T_list< Internal::null,
Internal::null > 
T_ListEnd
 

Functions

template<int D>
TooN::Matrix< D > computeRotation (const std::vector< TooN::Vector< D > > &a, const std::vector< TooN::Vector< D > > &b)
 
TooN::SO3 computeOrientation (const std::vector< TooN::Vector< 3 > > &a, const std::vector< TooN::Vector< 3 > > &b)
 
TooN::SO2 computeOrientation (const std::vector< TooN::Vector< 2 > > &a, const std::vector< TooN::Vector< 2 > > &b)
 
TooN::SO3 computeOrientation (const TooN::Vector< 3 > &a1, const TooN::Vector< 3 > &b1, const TooN::Vector< 3 > &a2, const TooN::Vector< 3 > &b2)
 
template<int D>
std::pair< TooN::Matrix< D >
, TooN::Vector< D > > 
computeAbsoluteOrientation (const std::vector< TooN::Vector< D > > &a, const std::vector< TooN::Vector< D > > &b)
 
TooN::SE3 computeAbsoluteOrientation (const std::vector< TooN::Vector< 3 > > &a, const std::vector< TooN::Vector< 3 > > &b)
 
TooN::SE2 computeAbsoluteOrientation (const std::vector< TooN::Vector< 2 > > &a, const std::vector< TooN::Vector< 2 > > &b)
 
template<int D>
std::tr1::tuple< TooN::Matrix
< D >, TooN::Vector< D >
, TooN::DefaultPrecision > 
computeSimilarity (const std::vector< TooN::Vector< D > > &a, const std::vector< TooN::Vector< D > > &b)
 
TooN::SIM3 computeSimilarity (const std::vector< TooN::Vector< 3 > > &a, const std::vector< TooN::Vector< 3 > > &b)
 
TooN::SIM2 computeSimilarity (const std::vector< TooN::Vector< 2 > > &a, const std::vector< TooN::Vector< 2 > > &b)
 
TooN::SO3 computeMeanOrientation (const std::vector< TooN::SO3<> > &r)
 
TooN::Matrix< 3 > quaternionToMatrix (const TooN::Vector< 4 > &q)
 
std::vector< TooN::Matrix< 3 > > five_point (const std::tr1::array< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > >, 5 > &points)
 
std::vector< TooN::SE3<> > se3_from_E (const TooN::Matrix< 3 > &E)
 
TooN::SE3 optimize_epipolar (const std::vector< std::pair< TooN::Vector< 3 >, TooN::Vector< 3 > > > &points, const TooN::SE3<> &initial)
 
std::pair< double, double > essential_reprojection_errors_squared (const TooN::Matrix< 3 > &E, const TooN::Vector< 3 > &q, const TooN::Vector< 3 > &p)
 
std::pair< double, double > essential_reprojection_errors (const TooN::Matrix< 3 > &E, const TooN::Vector< 3 > &q, const TooN::Vector< 3 > &p)
 
template<typename A , typename m >
struct mem_data_ref_t< A, m > mem_data_ref (m A::*data)
 
template<typename A , typename m >
struct const_mem_data_ref_t< A, m > const_mem_data_ref (const m A::*data)
 
template<typename A , typename m >
struct mem_data_t< A, m > mem_data (m A::*data)
 
template<typename A , typename m >
struct const_mem_data_t< A, m > const_mem_data (const m A::*data)
 
template<typename G , typename F >
struct bind_t< G, F > bind (const G &g, const F &f)
 
template<typename It , typename m >
struct member_iterator_t< It, m > member_const_iterator (const It &it, m std::iterator_traits< It >::value_type::*d)
 
template<typename It , typename m >
struct member_iterator_t< It, m > member_iterator (It it, m std::iterator_traits< It >::value_type::*d)
 
TooN::SE3 fourPointPose (const std::vector< TooN::Vector< 3 > > &points, const std::vector< TooN::Vector< 3 > > &pixels, bool &valid, const double angularError=0.14)
 
TooN::SE3 fourPointPoseFromCamera (const std::vector< TooN::Vector< 3 > > &points, const std::vector< TooN::Vector< 3 > > &pixels, bool &valid, const double angularError=0.14)
 
TooN::SE3 computeHandEyeSingle (const std::vector< TooN::SE3<> > &AB, const std::vector< TooN::SE3<> > &CD)
 
std::pair< TooN::SE3
<>, TooN::SE3<> > 
computeHandEye (const std::vector< TooN::SE3<> > &AB, const std::vector< TooN::SE3<> > &CD)
 
TooN::SO3 computeHandEyeSingle (const std::vector< TooN::SO3<> > &AB, const std::vector< TooN::SO3<> > &CD)
 
std::pair< TooN::SO3
<>, TooN::SO3<> > 
computeHandEye (const std::vector< TooN::SO3<> > &AB, const std::vector< TooN::SO3<> > &CD)
 
template<class T >
const T::first_type & first_point (const T &t)
 
template<class T >
const T::second_type & second_point (const T &t)
 
template<class T >
double noise (const T &t)
 
template<class It >
void getProjectiveHomography (It begin, It end, TooN::Matrix< 3 > &H)
 
template<class It >
TooN::Matrix< 3 > getProjectiveHomography (It begin, It end)
 
template<class V , class M >
void getCrossProductMatrix (const V &vec, M &result)
 
template<class V >
TooN::Matrix< 3 > getCrossProductMatrix (const V &vec)
 
template<class M >
void getEssentialMatrix (const TooN::SE3<> &transform, M &E)
 
TooN::Matrix< 3 > getEssentialMatrix (const TooN::SE3<> &transform)
 
template<typename A , typename B , typename C , typename D , typename ABase , typename BBase , typename CBase , typename DBase >
bool intersect_plane_line (const TooN::Vector< 3, A, ABase > &normal, const double d, const TooN::Vector< 3, B, BBase > &p1, const TooN::Vector< 3, C, CBase > &p2, TooN::Vector< 3, D, DBase > &i)
 
bool intersect_triangle (const TooN::Vector< 3 > &orig, const TooN::Vector< 3 > &dir, const TooN::Vector< 3 > &vert0, const TooN::Vector< 3 > &vert1, const TooN::Vector< 3 > &vert2, double &t, double &u, double &v)
 
bool intersect_culled_triangle (const TooN::Vector< 3 > &orig, const TooN::Vector< 3 > &dir, const TooN::Vector< 3 > &vert0, const TooN::Vector< 3 > &vert1, const TooN::Vector< 3 > &vert2, double &t, double &u, double &v)
 
bool intersect_triangles (const TooN::Vector< 3 > &v1, const TooN::Vector< 3 > &v2, const TooN::Vector< 3 > &v3, const TooN::Vector< 3 > &w1, const TooN::Vector< 3 > &w2, const TooN::Vector< 3 > &w3, TooN::Vector< 3 > &p1, TooN::Vector< 3 > &p2)
 
template<class A , class B , class C , class D >
void vfPrintf (std::basic_ostream< A, B > &o, const std::string fmt, const T_list< C, D > &l)
 
template<class C , class D >
void vPrintf (const std::string fmt, const T_list< C, D > &l)
 
template<class C , class D >
std::string vsPrintf (const std::string &fmt, const T_list< C, D > &l)
 
double eval_quartic (double B, double C, double D, double E, double x)
 A function to evaluate x^4 + Bx^3 + Cx^2 + Dx + E. More...
 
double newton_quartic (double B, double C, double D, double E, double x)
 A function that performs one iteration of Newton's method on the quartic x^4 + Bx^3 + Cx^2 + Dx + E. More...
 
int find_quartic_real_roots (double B, double C, double D, double E, double r[])
 
template<class T , class I >
void randomTuple (const std::vector< T > &cdf, std::vector< I > &t, T maxp)
 
template<class T >
void randomTuple (T &t, unsigned int bound)
 
template<class Obs , class Trans , class Tol >
size_t find_RANSAC_inliers (const std::vector< Obs > &observations, const Tol &tolerance, size_t N, Trans &best, std::vector< bool > &inlier, int sample_size=Trans::hypothesis_size)
 
template<class Obs , class Trans , class Tol >
size_t find_RANSAC_inliers (const std::vector< Obs > &observations, int sample_size, const Tol &tolerance, size_t N, Trans &best, std::vector< bool > &inlier)
 
template<class Obs , class Trans , class Tol >
double find_MSAC_inliers (const std::vector< Obs > &observations, const Tol &tolerance, size_t N, Trans &best, std::vector< bool > &inlier, int sample_size=Trans::hypothesis_size)
 
template<class Obs , class Trans , class Tol >
double find_MSAC_inliers (const std::vector< Obs > &observations, int sample_size, const Tol &tolerance, size_t N, Trans &best, std::vector< bool > &inlier)
 
double getShrinkRatio (unsigned int H, unsigned int N, unsigned int B)
 
template<class Obs , class Trans , class Tol , class Prob >
size_t find_RANSAC_inliers_guided_breadth_first (const std::vector< Obs > &observations, const Prob &prob, const Tol &tolerance, size_t N, size_t block_size, Trans &best, std::vector< bool > &inlier, int sample_size=Trans::hypothesis_size)
 
template<class Obs , class Trans , class Tol , class Prob >
size_t find_RANSAC_inliers_guided_breadth_first (const std::vector< Obs > &observations, const Prob &prob, int sample_size, const Tol &tolerance, size_t N, size_t block_size, Trans &best, std::vector< bool > &inlier)
 
template<class Obs , class Trans , class Tol >
size_t find_RANSAC_inliers_breadth_first (const std::vector< Obs > &observations, const Tol &tolerance, size_t N, size_t block_size, Trans &best, std::vector< bool > &inlier, int sample_size=Trans::hypothesis_size)
 
template<class Obs , class Trans , class Tol >
size_t find_RANSAC_inliers_breadth_first (const std::vector< Obs > &observations, int sample_size, const Tol &tolerance, size_t N, size_t block_size, Trans &best, std::vector< bool > &inlier)
 
template<class T , class U >
void remove_if_false (std::vector< T > &v, const std::vector< U > &flag)
 
template<class A , class B >
Internal::refpair< A, B > rpair (A &aa, B &bb)
 
int three_point_pose (const TooN::Vector< 3 > x[], const TooN::Vector< 2 > z[], std::vector< TooN::SE3<> > &poses)
 
int three_point_pose (const TooN::Vector< 3 > x[], const TooN::Vector< 3 > rays[], std::vector< TooN::SE3<> > &poses)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void unscentedTransformSqrt (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &L, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void unscentedTransformSqrt (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &L, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP, TooN::FixedMatrix< M, N, M3 > &cov)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void sphericalUnscentedTransformSqrt (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &L, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void sphericalUnscentedTransformSqrt (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &L, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP, TooN::FixedMatrix< M, N, M3 > &cov)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void unscentedTransform (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &P, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void unscentedTransform (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &P, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP, TooN::FixedMatrix< M, N, M3 > &cov)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void sphericalUnscentedTransform (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &P, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP)
 
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void sphericalUnscentedTransform (const TooN::FixedVector< N, V1 > &x, const TooN::FixedMatrix< N, N, M1 > &P, const F &f, TooN::FixedVector< M, V2 > &newx, TooN::FixedMatrix< M, M, M2 > &newP, TooN::FixedMatrix< M, N, M3 > &cov)
 
template<int N, int M, class Ax , class AP , class AR , class F >
void unscentedKalmanUpdate (TooN::FixedVector< N, Ax > &x, TooN::FixedMatrix< N, N, AP > &P, const F &f, const TooN::FixedMatrix< M, M, AR > &R)
 
static TooN::SO3 canonicalOrientation (const TooN::Vector< 3 > &a, const TooN::Vector< 3 > &b)
 
void build_matrix (const Vector< 9 > &X, const Vector< 9 > &Y, const Vector< 9 > &Z, const Vector< 9 > &W, Matrix< 10, 20 > &R)
 
Vector< 9 > stack_points (const Vector< 3 > &p, const Vector< 3 > &q)
 
template<int AN, int BN>
Vector< AN+BN-1 > poly_mul (const Vector< AN > &a, const Vector< BN > &b)
 
template<int N>
double polyval (const Vector< N > &v, double x)
 
Matrix< 3, 3, double,
Reference::RowMajor > 
as_matrix (Vector< 9 > &v)
 
template<int R, int C, class P >
Matrix< C-R, C, P > dodgy_null (Matrix< R, C, P > m)
 
vector< Matrix< 3 > > five_point (const array< pair< Vector< 3 >, Vector< 3 > >, 5 > &points)
 
double point_line_distance_squared (Vector< 3 > point, const Vector< 3 > &line)
 
double point_line_distance (Vector< 3 > point, const Vector< 3 > &line)
 
pair< double, double > essential_reprojection_errors_squared (const Matrix< 3 > &E, const Vector< 3 > &q, const Vector< 3 > &p)
 
pair< double, double > essential_reprojection_errors (const Matrix< 3 > &E, const Vector< 3 > &q, const Vector< 3 > &p)
 
static bool computeDistances (const double xx, const double x, const double angle, const double distance, const double angularError, TooN::Vector< 2 > &roots)
 
static TooN::Vector< 5 > getACoeffs (double c1, double c2, double c3, double d1, double d2, double d3)
 
static TooN::Vector< 3 > getBCoeffs (int i, int j, int k, int l, const TooN::Vector< 5 > &v4, const TooN::Vector< 5 > &v5)
 
static bool fourPointSolver (const std::vector< TooN::Vector< 3 > > &points, std::vector< TooN::Vector< 3 > > &myPixels, TooN::Vector< 6 > &distances, std::vector< TooN::Vector< 2 > > &length, const double angularError)
 
static Vector< 3 > getRotationVector (const SO3<> &r)
 
static Vector< 3 > getRotationVector (const SE3<> &t)
 
template<class T >
static TooN::SO3 solveXABX (const std::vector< T > &A, const std::vector< T > &B)
 
static Matrix< 3 > eyeMinus (const Matrix< 3 > &m)
 
SE3 computeHandEyeSingle (const vector< SE3<> > &AB, const vector< SE3<> > &CD)
 
SO3 computeHandEyeSingle (const vector< SO3<> > &AB, const vector< SO3<> > &CD)
 
static int depressed_cubic_real_roots (double P, double Q, double r[])
 
static double square (double x)
 
static SE3 three_point_absolute_orientation (const Vector< 3 > x[], const Vector< 3 > y[])
 
int three_point_pose (const Vector< 3 > xi[], const Vector< 2 > zi[], vector< SE3<> > &poses)
 

Variables

static const T_ListEnd Fmt =TupleHead
 
static struct Internal::add_fill_s add_fill
 
static struct
Internal::like_print_s 
print
 
static struct Internal::no_space_s no_space
 
static const T_ListEnd TupleHead =T_ListEnd(Internal::null(), Internal::null())
 

Function Documentation

Matrix<3, 3, double, Reference::RowMajor> tag::as_matrix ( Vector< 9 > &  v)

Referenced by five_point().

void tag::build_matrix ( const Vector< 9 > &  X,
const Vector< 9 > &  Y,
const Vector< 9 > &  Z,
const Vector< 9 > &  W,
Matrix< 10, 20 > &  R 
)

Referenced by five_point().

static TooN::SO3 tag::canonicalOrientation ( const TooN::Vector< 3 > &  a,
const TooN::Vector< 3 > &  b 
)
inlinestatic

Referenced by computeOrientation().

static bool tag::computeDistances ( const double  xx,
const double  x,
const double  angle,
const double  distance,
const double  angularError,
TooN::Vector< 2 > &  roots 
)
inlinestatic

Referenced by fourPointSolver().

SE3 tag::computeHandEyeSingle ( const vector< SE3<> > &  AB,
const vector< SE3<> > &  CD 
)

References eyeMinus(), and solveXABX().

SO3 tag::computeHandEyeSingle ( const vector< SO3<> > &  AB,
const vector< SO3<> > &  CD 
)

References solveXABX().

static int tag::depressed_cubic_real_roots ( double  P,
double  Q,
double  r[] 
)
static

Referenced by find_quartic_real_roots().

template<int R, int C, class P >
Matrix<C-R, C, P> tag::dodgy_null ( Matrix< R, C, P >  m)

Referenced by five_point().

pair<double, double> tag::essential_reprojection_errors ( const Matrix< 3 > &  E,
const Vector< 3 > &  q,
const Vector< 3 > &  p 
)

References point_line_distance().

pair<double, double> tag::essential_reprojection_errors_squared ( const Matrix< 3 > &  E,
const Vector< 3 > &  q,
const Vector< 3 > &  p 
)
double tag::eval_quartic ( double  B,
double  C,
double  D,
double  E,
double  x 
)
inline

A function to evaluate x^4 + Bx^3 + Cx^2 + Dx + E.

static Matrix<3> tag::eyeMinus ( const Matrix< 3 > &  m)
inlinestatic

Referenced by computeHandEyeSingle().

template<class T >
const T::first_type& tag::first_point ( const T &  t)
inline
vector<Matrix<3> > tag::five_point ( const array< pair< Vector< 3 >, Vector< 3 > >, 5 > &  points)
static bool tag::fourPointSolver ( const std::vector< TooN::Vector< 3 > > &  points,
std::vector< TooN::Vector< 3 > > &  myPixels,
TooN::Vector< 6 > &  distances,
std::vector< TooN::Vector< 2 > > &  length,
const double  angularError 
)
static
static TooN::Vector<5> tag::getACoeffs ( double  c1,
double  c2,
double  c3,
double  d1,
double  d2,
double  d3 
)
inlinestatic

Referenced by fourPointSolver().

static TooN::Vector<3> tag::getBCoeffs ( int  i,
int  j,
int  k,
int  l,
const TooN::Vector< 5 > &  v4,
const TooN::Vector< 5 > &  v5 
)
inlinestatic

Referenced by fourPointSolver().

static Vector<3> tag::getRotationVector ( const SO3<> &  r)
inlinestatic

Referenced by getRotationVector(), and solveXABX().

static Vector<3> tag::getRotationVector ( const SE3<> &  t)
inlinestatic

References getRotationVector().

double tag::getShrinkRatio ( unsigned int  H,
unsigned int  N,
unsigned int  B 
)
inline
double tag::newton_quartic ( double  B,
double  C,
double  D,
double  E,
double  x 
)
inline

A function that performs one iteration of Newton's method on the quartic x^4 + Bx^3 + Cx^2 + Dx + E.

Referenced by three_point_pose().

template<class T >
double tag::noise ( const T &  t)
inline
double tag::point_line_distance ( Vector< 3 >  point,
const Vector< 3 > &  line 
)
double tag::point_line_distance_squared ( Vector< 3 >  point,
const Vector< 3 > &  line 
)
template<int AN, int BN>
Vector<AN+BN-1> tag::poly_mul ( const Vector< AN > &  a,
const Vector< BN > &  b 
)
template<int N>
double tag::polyval ( const Vector< N > &  v,
double  x 
)
template<class T , class I >
void tag::randomTuple ( const std::vector< T > &  cdf,
std::vector< I > &  t,
maxp 
)
template<class T >
void tag::randomTuple ( T &  t,
unsigned int  bound 
)
template<class A , class B >
Internal::refpair<A,B> tag::rpair ( A &  aa,
B &  bb 
)

Similar to std::make_pair, but for references. This can be used for multiple return values:

float f;
int i;
rpair(f,i) = make_pair(2.2f, 1);
Parameters
aafirst value
bbsecond value
template<class T >
const T::second_type& tag::second_point ( const T &  t)
inline
template<class T >
static TooN::SO3 tag::solveXABX ( const std::vector< T > &  A,
const std::vector< T > &  B 
)
inlinestatic
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void tag::sphericalUnscentedTransformSqrt ( const TooN::FixedVector< N, V1 > &  x,
const TooN::FixedMatrix< N, N, M1 > &  L,
const F &  f,
TooN::FixedVector< M, V2 > &  newx,
TooN::FixedMatrix< M, M, M2 > &  newP 
)
template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void tag::sphericalUnscentedTransformSqrt ( const TooN::FixedVector< N, V1 > &  x,
const TooN::FixedMatrix< N, N, M1 > &  L,
const F &  f,
TooN::FixedVector< M, V2 > &  newx,
TooN::FixedMatrix< M, M, M2 > &  newP,
TooN::FixedMatrix< M, N, M3 > &  cov 
)
static double tag::square ( double  x)
inlinestatic

Referenced by three_point_pose().

Vector<9> tag::stack_points ( const Vector< 3 > &  p,
const Vector< 3 > &  q 
)

Referenced by five_point().

static SE3 tag::three_point_absolute_orientation ( const Vector< 3 >  x[],
const Vector< 3 >  y[] 
)
static

Referenced by three_point_pose().

int tag::three_point_pose ( const Vector< 3 >  xi[],
const Vector< 2 >  zi[],
vector< SE3<> > &  poses 
)
template<int N, int M, class Ax , class AP , class AR , class F >
void tag::unscentedKalmanUpdate ( TooN::FixedVector< N, Ax > &  x,
TooN::FixedMatrix< N, N, AP > &  P,
const F &  f,
const TooN::FixedMatrix< M, M, AR > &  R 
)

References unscentedTransform().

template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 >
void tag::unscentedTransformSqrt ( const TooN::FixedVector< N, V1 > &  x,
const TooN::FixedMatrix< N, N, M1 > &  L,
const F &  f,
TooN::FixedVector< M, V2 > &  newx,
TooN::FixedMatrix< M, M, M2 > &  newP 
)

Referenced by unscentedTransform().

template<int N, int M, class F , class V1 , class V2 , class M1 , class M2 , class M3 >
void tag::unscentedTransformSqrt ( const TooN::FixedVector< N, V1 > &  x,
const TooN::FixedMatrix< N, N, M1 > &  L,
const F &  f,
TooN::FixedVector< M, V2 > &  newx,
TooN::FixedMatrix< M, M, M2 > &  newP,
TooN::FixedMatrix< M, N, M3 > &  cov 
)