#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_ |
using Sophus::LieGroupTests< LieGroup_ >::Adjoint = typename LieGroup::Adjoint |
using Sophus::LieGroupTests< LieGroup_ >::ConstPointMap = Eigen::Map<const Point> |
using Sophus::LieGroupTests< LieGroup_ >::HomogeneousPoint = typename LieGroup::HomogeneousPoint |
using Sophus::LieGroupTests< LieGroup_ >::LieGroup = LieGroup_ |
using Sophus::LieGroupTests< LieGroup_ >::Line = typename LieGroup::Line |
using Sophus::LieGroupTests< LieGroup_ >::Point = typename LieGroup::Point |
using Sophus::LieGroupTests< LieGroup_ >::Scalar = typename LieGroup::Scalar |
using Sophus::LieGroupTests< LieGroup_ >::Tangent = typename LieGroup::Tangent |
using Sophus::LieGroupTests< LieGroup_ >::Transformation = typename LieGroup::Transformation |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inlineprivate |
|
inlineprivate |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
staticconstexpr |
|
private |
|
private |
|
private |
|
staticconstexpr |
|
staticconstexpr |
|
private |
|
private |