|
typedef typename std::enable_if< B, T >::type | enable_if_t |
|
typedef Eigen::Hyperplane< T, 2 > | Line2 |
|
typedef Line2< double > | Line2d |
|
typedef Line2< float > | Line2f |
|
typedef Eigen::Matrix< Scalar, M, N > | Matrix |
|
typedef Matrix< Scalar, 2, 2 > | Matrix2 |
|
typedef Matrix2< double > | Matrix2d |
|
typedef Matrix2< float > | Matrix2f |
|
typedef Matrix< Scalar, 3, 3 > | Matrix3 |
|
typedef Matrix3< double > | Matrix3d |
|
typedef Matrix3< float > | Matrix3f |
|
typedef Matrix< Scalar, 4, 4 > | Matrix4 |
|
typedef Matrix4< double > | Matrix4d |
|
typedef Matrix4< float > | Matrix4f |
|
typedef Matrix< Scalar, 6, 6 > | Matrix6 |
|
typedef Matrix6< double > | Matrix6d |
|
typedef Matrix6< float > | Matrix6f |
|
typedef Matrix< Scalar, 7, 7 > | Matrix7 |
|
typedef Matrix7< double > | Matrix7d |
|
typedef Matrix7< float > | Matrix7f |
|
typedef Eigen::ParametrizedLine< Scalar, N, Options > | ParametrizedLine |
|
typedef ParametrizedLine< Scalar, 2, Options > | ParametrizedLine2 |
|
typedef ParametrizedLine2< double > | ParametrizedLine2d |
|
typedef ParametrizedLine2< float > | ParametrizedLine2f |
|
typedef ParametrizedLine< Scalar, 3, Options > | ParametrizedLine3 |
|
typedef ParametrizedLine3< double > | ParametrizedLine3d |
|
typedef ParametrizedLine3< float > | ParametrizedLine3f |
|
typedef Eigen::Hyperplane< T, 3 > | Plane3 |
|
typedef Plane3< double > | Plane3d |
|
typedef Plane3< float > | Plane3f |
|
typedef RxSO2< double > | RxSO2d |
|
typedef RxSO2< float > | RxSO2f |
|
typedef RxSO3< double > | RxSO3d |
|
typedef RxSO3< float > | RxSO3f |
|
typedef SE2< double > | SE2d |
|
typedef SE2< float > | SE2f |
|
typedef SE3< double > | SE3d |
|
typedef SE3< float > | SE3f |
|
typedef Sim2< double > | Sim2d |
|
typedef Sim2< float > | Sim2f |
|
typedef Sim3< double > | Sim3d |
|
typedef Sim3< float > | Sim3f |
|
typedef SO2< double > | SO2d |
|
typedef SO2< float > | SO2f |
|
typedef SO3< double > | SO3d |
|
typedef SO3< float > | SO3f |
|
typedef Eigen::Matrix< Scalar, M, 1, Options > | Vector |
|
typedef Vector< Scalar, 2, Options > | Vector2 |
|
typedef Vector2< double > | Vector2d |
|
typedef Vector2< float > | Vector2f |
|
typedef Vector< Scalar, 3, Options > | Vector3 |
|
typedef Vector3< double > | Vector3d |
|
typedef Vector3< float > | Vector3f |
|
typedef Vector< Scalar, 4 > | Vector4 |
|
typedef Vector4< double > | Vector4d |
|
typedef Vector4< float > | Vector4f |
|
typedef Vector< Scalar, 6 > | Vector6 |
|
typedef Vector6< double > | Vector6d |
|
typedef Vector6< float > | Vector6f |
|
typedef Vector< Scalar, 7 > | Vector7 |
|
typedef Vector7< double > | Vector7d |
|
typedef Vector7< float > | Vector7f |
|
|
enable_if_t< std::is_same< typename SequenceContainer::value_type, SO2< Scalar > >::value, optional< typename SequenceContainer::value_type > > | average (SequenceContainer const &foo_Ts_bar) |
|
enable_if_t< std::is_same< typename SequenceContainer::value_type, SE2< Scalar > >::value, optional< typename SequenceContainer::value_type > > | average (SequenceContainer const &foo_Ts_bar, int max_num_iterations=20) |
|
auto | curveNumDiff (Fn curve, Scalar t, Scalar h=Constants< Scalar >::epsilonSqrt()) -> decltype(details::Curve< Scalar >::num_diff(std::move(curve), t, h)) |
|
SOPHUS_FUNC void | defaultEnsure (char const *function, char const *file, int line, char const *description, Args &&... args) |
|
void | ensureFailed (char const *function, char const *file, int line, char const *description) |
|
std::vector< SE2< T >, Eigen::aligned_allocator< SE2< T > > > | getTestSE2s () |
|
std::vector< SE3< Scalar >, Eigen::aligned_allocator< SE3< Scalar > > > | getTestSE3s () |
|
enable_if_t< interp_details::Traits< G >::supported, G > | interpolate (G const &foo_T_bar, G const &foo_T_baz, Scalar2 p=Scalar2(0.5f)) |
|
SOPHUS_FUNC bool | isOrthogonal (Eigen::MatrixBase< D > const &R) |
|
SOPHUS_FUNC bool | isScaledOrthogonalAndPositive (Eigen::MatrixBase< D > const &sR) |
|
optional< typename SequenceContainer::value_type > | iterativeMean (SequenceContainer const &foo_Ts_bar, int max_num_iterations) |
|
Line2< T > | lineFromSE2 (SE2< T > const &T_foo_line) |
|
Eigen::Hyperplane< T, N > | makeHyperplaneUnique (Eigen::Hyperplane< T, N > const &plane) |
|
SOPHUS_FUNC enable_if_t< std::is_floating_point< typename D::Scalar >::value, Matrix< typename D::Scalar, D::RowsAtCompileTime, D::RowsAtCompileTime > > | makeRotationMatrix (Eigen::MatrixBase< D > const &R) |
|
auto | maxMetric (T const &p0, T const &p1) -> decltype(details::MaxMetric< T >::impl(p0, p1)) |
|
Vector2< T > | normalFromSO2 (SO2< T > const &R_foo_line) |
|
Vector3< T > | normalFromSO3 (SO3< T > const &R_foo_plane) |
|
template<typename OutputStream > |
OutputStream & | operator<< (OutputStream &ostream, SE3fFormatter &formatter) |
|
template<typename T > |
std::ostream & | operator<< (std::ostream &out, const SE2< T > &se2) |
|
template<typename T > |
std::ostream & | operator<< (std::ostream &out, const SE3< T > &se3) |
|
Plane3< T > | planeFromSE3 (SE3< T > const &T_foo_plane) |
|
void | processTestResult (bool passed) |
|
Matrix3< T > | rotationFromNormal (Vector3< T > const &normal_foo, Vector3< T > xDirHint_foo=Vector3< T >(T(1), T(0), T(0)), Vector3< T > yDirHint_foo=Vector3< T >(T(0), T(1), T(0))) |
|
SE2< T > | SE2FromLine (Line2< T > const &line_foo) |
|
SE3< T > | SE3FromPlane (Plane3< T > const &plane_foo) |
|
void | setElementAt (T &p, Scalar value, int i) |
|
void | setToZero (T &p) |
|
SO2< T > | SO2FromNormal (Vector2< T > normal_foo) |
|
SO3< T > | SO3FromNormal (Vector3< T > const &normal_foo) |
|
auto | squaredNorm (T const &p) -> decltype(details::SquaredNorm< T >::impl(p)) |
|
int | test_rxso2 () |
|
int | test_rxso3 () |
|
int | test_se2 () |
|
int | test_se3 () |
|
int | test_sim3 () |
|
int | test_so2 () |
|
int | test_so3 () |
|
Eigen::Vector3f | toPose2D (const Sophus::SE3f &pose) |
| Convert a full Sophus pose into a 2 dimensional pose. More...
|
|
Sophus::SE3f | toPose3D (const Eigen::Vector3f &pose) |
| Convert a 2 dimensional pose to a full Sophus pose in 3d. More...
|
|
auto | transpose (T const &p) -> decltype(details::Transpose< T >::impl(T())) |
|
Eigen::Matrix< Scalar, N, M > | vectorFieldNumDiff (Fn vector_field, ScalarOrVector const &a, Scalar eps=Constants< Scalar >::epsilonSqrt()) |
|