Public Types | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
Sophus::LieGroupTests< LieGroup_ > Class Template Reference

#include <tests.hpp>

Public Types

using Adjoint = typename LieGroup::Adjoint
 
using ConstPointMap = Eigen::Map< const Point >
 
using HomogeneousPoint = typename LieGroup::HomogeneousPoint
 
using LieGroup = LieGroup_
 
using Line = typename LieGroup::Line
 
using Point = typename LieGroup::Point
 
using Scalar = typename LieGroup::Scalar
 
using Tangent = typename LieGroup::Tangent
 
using Transformation = typename LieGroup::Transformation
 

Public Member Functions

template<class G = LieGroup>
enable_if_t< std::is_same< G, Sophus::SO2< Scalar > >::value||std::is_same< G, Sophus::SO3< Scalar > >::value||std::is_same< G, Sophus::SE2< Scalar > >::value||std::is_same< G, Sophus::SE3< Scalar > >::value, bool > additionalDerivativeTest ()
 
template<class G = LieGroup>
enable_if_t<!std::is_same< G, Sophus::SO2< Scalar > >::value &&!std::is_same< G, Sophus::SO3< Scalar > >::value &&!std::is_same< G, Sophus::SE2< Scalar > >::value &&!std::is_same< G, Sophus::SE3< Scalar > >::value, bool > additionalDerivativeTest ()
 
bool adjointTest ()
 
bool contructorAndAssignmentTest ()
 
bool derivativeTest ()
 
template<class S = Scalar>
enable_if_t< std::is_floating_point< S >::value, bool > doAllTestsPass ()
 
template<class S = Scalar>
enable_if_t<!std::is_floating_point< S >::value, bool > doAllTestsPass ()
 
bool expLogTest ()
 
bool expMapTest ()
 
bool groupActionTest ()
 
bool interpolateAndMeanTest ()
 
bool lieBracketTest ()
 
 LieGroupTests (std::vector< LieGroup, Eigen::aligned_allocator< LieGroup >> const &group_vec, std::vector< Tangent, Eigen::aligned_allocator< Tangent >> const &tangent_vec, std::vector< Point, Eigen::aligned_allocator< Point >> const &point_vec)
 
bool lineActionTest ()
 
bool newDeleteSmokeTest ()
 
bool productTest ()
 
bool testRandomSmoke ()
 
bool veeHatTest ()
 

Static Public Attributes

static constexpr int DoF = LieGroup::DoF
 
static constexpr int N = LieGroup::N
 
static constexpr int num_parameters = LieGroup::num_parameters
 

Private Member Functions

bool doesLargeTestSetPass ()
 
bool doesSmallTestSetPass ()
 
Eigen::Matrix< Scalar, N - 1, 1 > map (Eigen::Matrix< Scalar, N, N > const &T, Eigen::Matrix< Scalar, N - 1, 1 > const &p)
 
Eigen::Matrix< Scalar, N, 1 > map (Eigen::Matrix< Scalar, N, N > const &T, Eigen::Matrix< Scalar, N, 1 > const &p)
 

Private Attributes

std::vector< LieGroup, Eigen::aligned_allocator< LieGroup > > group_vec_
 
const Scalar kSmallEps = Constants<Scalar>::epsilon()
 
const Scalar kSmallEpsSqrt = Constants<Scalar>::epsilonSqrt()
 
std::vector< Point, Eigen::aligned_allocator< Point > > point_vec_
 
std::vector< Tangent, Eigen::aligned_allocator< Tangent > > tangent_vec_
 

Detailed Description

template<class LieGroup_>
class Sophus::LieGroupTests< LieGroup_ >

Definition at line 21 of file tests.hpp.

Member Typedef Documentation

◆ Adjoint

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Adjoint = typename LieGroup::Adjoint

Definition at line 31 of file tests.hpp.

◆ ConstPointMap

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::ConstPointMap = Eigen::Map<const Point>

Definition at line 29 of file tests.hpp.

◆ HomogeneousPoint

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::HomogeneousPoint = typename LieGroup::HomogeneousPoint

Definition at line 28 of file tests.hpp.

◆ LieGroup

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::LieGroup = LieGroup_

Definition at line 23 of file tests.hpp.

◆ Line

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Line = typename LieGroup::Line

Definition at line 30 of file tests.hpp.

◆ Point

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Point = typename LieGroup::Point

Definition at line 27 of file tests.hpp.

◆ Scalar

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Scalar = typename LieGroup::Scalar

Definition at line 24 of file tests.hpp.

◆ Tangent

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Tangent = typename LieGroup::Tangent

Definition at line 26 of file tests.hpp.

◆ Transformation

template<class LieGroup_ >
using Sophus::LieGroupTests< LieGroup_ >::Transformation = typename LieGroup::Transformation

Definition at line 25 of file tests.hpp.

Constructor & Destructor Documentation

◆ LieGroupTests()

template<class LieGroup_ >
Sophus::LieGroupTests< LieGroup_ >::LieGroupTests ( std::vector< LieGroup, Eigen::aligned_allocator< LieGroup >> const &  group_vec,
std::vector< Tangent, Eigen::aligned_allocator< Tangent >> const &  tangent_vec,
std::vector< Point, Eigen::aligned_allocator< Point >> const &  point_vec 
)
inline

Definition at line 36 of file tests.hpp.

Member Function Documentation

◆ additionalDerivativeTest() [1/2]

template<class LieGroup_ >
template<class G = LieGroup>
enable_if_t<std::is_same<G, Sophus::SO2<Scalar> >::value || std::is_same<G, Sophus::SO3<Scalar> >::value || std::is_same<G, Sophus::SE2<Scalar> >::value || std::is_same<G, Sophus::SE3<Scalar> >::value, bool> Sophus::LieGroupTests< LieGroup_ >::additionalDerivativeTest ( )
inline

Definition at line 140 of file tests.hpp.

◆ additionalDerivativeTest() [2/2]

template<class LieGroup_ >
template<class G = LieGroup>
enable_if_t<!std::is_same<G, Sophus::SO2<Scalar> >::value && !std::is_same<G, Sophus::SO3<Scalar> >::value && !std::is_same<G, Sophus::SE2<Scalar> >::value && !std::is_same<G, Sophus::SE3<Scalar> >::value, bool> Sophus::LieGroupTests< LieGroup_ >::additionalDerivativeTest ( )
inline

Definition at line 191 of file tests.hpp.

◆ adjointTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::adjointTest ( )
inline

Definition at line 46 of file tests.hpp.

◆ contructorAndAssignmentTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::contructorAndAssignmentTest ( )
inline

Definition at line 66 of file tests.hpp.

◆ derivativeTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::derivativeTest ( )
inline

Definition at line 113 of file tests.hpp.

◆ doAllTestsPass() [1/2]

template<class LieGroup_ >
template<class S = Scalar>
enable_if_t<std::is_floating_point<S>::value, bool> Sophus::LieGroupTests< LieGroup_ >::doAllTestsPass ( )
inline

Definition at line 452 of file tests.hpp.

◆ doAllTestsPass() [2/2]

template<class LieGroup_ >
template<class S = Scalar>
enable_if_t<!std::is_floating_point<S>::value, bool> Sophus::LieGroupTests< LieGroup_ >::doAllTestsPass ( )
inline

Definition at line 457 of file tests.hpp.

◆ doesLargeTestSetPass()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::doesLargeTestSetPass ( )
inlineprivate

Definition at line 476 of file tests.hpp.

◆ doesSmallTestSetPass()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::doesSmallTestSetPass ( )
inlineprivate

Definition at line 462 of file tests.hpp.

◆ expLogTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::expLogTest ( )
inline

Definition at line 209 of file tests.hpp.

◆ expMapTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::expMapTest ( )
inline

Definition at line 221 of file tests.hpp.

◆ groupActionTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::groupActionTest ( )
inline

Definition at line 233 of file tests.hpp.

◆ interpolateAndMeanTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::interpolateAndMeanTest ( )
inline

Definition at line 323 of file tests.hpp.

◆ lieBracketTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::lieBracketTest ( )
inline

Definition at line 287 of file tests.hpp.

◆ lineActionTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::lineActionTest ( )
inline

Definition at line 261 of file tests.hpp.

◆ map() [1/2]

template<class LieGroup_ >
Eigen::Matrix<Scalar, N - 1, 1> Sophus::LieGroupTests< LieGroup_ >::map ( Eigen::Matrix< Scalar, N, N > const &  T,
Eigen::Matrix< Scalar, N - 1, 1 > const &  p 
)
inlineprivate

Definition at line 490 of file tests.hpp.

◆ map() [2/2]

template<class LieGroup_ >
Eigen::Matrix<Scalar, N, 1> Sophus::LieGroupTests< LieGroup_ >::map ( Eigen::Matrix< Scalar, N, N > const &  T,
Eigen::Matrix< Scalar, N, 1 > const &  p 
)
inlineprivate

Definition at line 497 of file tests.hpp.

◆ newDeleteSmokeTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::newDeleteSmokeTest ( )
inline

Definition at line 314 of file tests.hpp.

◆ productTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::productTest ( )
inline

Definition at line 195 of file tests.hpp.

◆ testRandomSmoke()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::testRandomSmoke ( )
inline

Definition at line 441 of file tests.hpp.

◆ veeHatTest()

template<class LieGroup_ >
bool Sophus::LieGroupTests< LieGroup_ >::veeHatTest ( )
inline

Definition at line 304 of file tests.hpp.

Member Data Documentation

◆ DoF

template<class LieGroup_ >
constexpr int Sophus::LieGroupTests< LieGroup_ >::DoF = LieGroup::DoF
staticconstexpr

Definition at line 33 of file tests.hpp.

◆ group_vec_

template<class LieGroup_ >
std::vector<LieGroup, Eigen::aligned_allocator<LieGroup> > Sophus::LieGroupTests< LieGroup_ >::group_vec_
private

Definition at line 502 of file tests.hpp.

◆ kSmallEps

template<class LieGroup_ >
const Scalar Sophus::LieGroupTests< LieGroup_ >::kSmallEps = Constants<Scalar>::epsilon()
private

Definition at line 487 of file tests.hpp.

◆ kSmallEpsSqrt

template<class LieGroup_ >
const Scalar Sophus::LieGroupTests< LieGroup_ >::kSmallEpsSqrt = Constants<Scalar>::epsilonSqrt()
private

Definition at line 488 of file tests.hpp.

◆ N

template<class LieGroup_ >
constexpr int Sophus::LieGroupTests< LieGroup_ >::N = LieGroup::N
staticconstexpr

Definition at line 32 of file tests.hpp.

◆ num_parameters

template<class LieGroup_ >
constexpr int Sophus::LieGroupTests< LieGroup_ >::num_parameters = LieGroup::num_parameters
staticconstexpr

Definition at line 34 of file tests.hpp.

◆ point_vec_

template<class LieGroup_ >
std::vector<Point, Eigen::aligned_allocator<Point> > Sophus::LieGroupTests< LieGroup_ >::point_vec_
private

Definition at line 504 of file tests.hpp.

◆ tangent_vec_

template<class LieGroup_ >
std::vector<Tangent, Eigen::aligned_allocator<Tangent> > Sophus::LieGroupTests< LieGroup_ >::tangent_vec_
private

Definition at line 503 of file tests.hpp.


The documentation for this class was generated from the following file:


sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48