Namespaces | Classes | Typedefs | Functions | Variables
Sophus Namespace Reference

Namespaces

 details
 
 experimental
 
 interp_details
 
 test
 

Classes

struct  Constants
 
struct  Constants< float >
 
struct  GetScalar
 
struct  GetScalar< Matrix< Scalar_, M, N > >
 
struct  IsFixedSizeVector
 
struct  IsFloatingPoint
 
struct  IsFloatingPoint< Matrix< Scalar, M, N > >
 
struct  IsUniformRandomBitGenerator
 
class  LieGroupTests
 
struct  nullopt_t
 Nullopt type of lightweight optional class. More...
 
class  optional
 
class  RxSO2
 RxSO2 using storage; derived from RxSO2Base. More...
 
class  RxSO2Base
 
class  RxSO3
 RxSO3 using storage; derived from RxSO3Base. More...
 
class  RxSO3Base
 
class  SE2
 SE2 using default storage; derived from SE2Base. More...
 
class  SE2Base
 
class  SE3
 SE3 using default storage; derived from SE3Base. More...
 
class  SE3Base
 
class  Sim2
 Sim2 using default storage; derived from Sim2Base. More...
 
class  Sim2Base
 
class  Sim3
 Sim3 using default storage; derived from Sim3Base. More...
 
class  Sim3Base
 
class  SO2
 SO2 using default storage; derived from SO2Base. More...
 
class  SO2Base
 
class  SO3
 SO3 using default storage; derived from SO3Base. More...
 
class  SO3Base
 
class  Tests
 

Typedefs

template<bool B, class T = void>
using enable_if_t = typename std::enable_if< B, T >::type
 
template<class T >
using Line2 = Eigen::Hyperplane< T, 2 >
 Lines in 2d are hyperplanes. More...
 
using Line2d = Line2< double >
 
using Line2f = Line2< float >
 
template<class Scalar , int M, int N>
using Matrix = Eigen::Matrix< Scalar, M, N >
 
template<class Scalar >
using Matrix2 = Matrix< Scalar, 2, 2 >
 
using Matrix2d = Matrix2< double >
 
using Matrix2f = Matrix2< float >
 
template<class Scalar >
using Matrix3 = Matrix< Scalar, 3, 3 >
 
using Matrix3d = Matrix3< double >
 
using Matrix3f = Matrix3< float >
 
template<class Scalar >
using Matrix4 = Matrix< Scalar, 4, 4 >
 
using Matrix4d = Matrix4< double >
 
using Matrix4f = Matrix4< float >
 
template<class Scalar >
using Matrix6 = Matrix< Scalar, 6, 6 >
 
using Matrix6d = Matrix6< double >
 
using Matrix6f = Matrix6< float >
 
template<class Scalar >
using Matrix7 = Matrix< Scalar, 7, 7 >
 
using Matrix7d = Matrix7< double >
 
using Matrix7f = Matrix7< float >
 
template<class Scalar , int N, int Options = 0>
using ParametrizedLine = Eigen::ParametrizedLine< Scalar, N, Options >
 
template<class Scalar , int Options = 0>
using ParametrizedLine2 = ParametrizedLine< Scalar, 2, Options >
 
using ParametrizedLine2d = ParametrizedLine2< double >
 
using ParametrizedLine2f = ParametrizedLine2< float >
 
template<class Scalar , int Options = 0>
using ParametrizedLine3 = ParametrizedLine< Scalar, 3, Options >
 
using ParametrizedLine3d = ParametrizedLine3< double >
 
using ParametrizedLine3f = ParametrizedLine3< float >
 
template<class T >
using Plane3 = Eigen::Hyperplane< T, 3 >
 Planes in 3d are hyperplanes. More...
 
using Plane3d = Plane3< double >
 
using Plane3f = Plane3< float >
 
using RxSO2d = RxSO2< double >
 
using RxSO2f = RxSO2< float >
 
using RxSO3d = RxSO3< double >
 
using RxSO3f = RxSO3< float >
 
using SE2d = SE2< double >
 
using SE2f = SE2< float >
 
using SE3d = SE3< double >
 
using SE3f = SE3< float >
 
using Sim2d = Sim2< double >
 
using Sim2f = Sim2< float >
 
using Sim3d = Sim3< double >
 
using Sim3f = Sim3< float >
 
using SO2d = SO2< double >
 
using SO2f = SO2< float >
 
using SO3d = SO3< double >
 
using SO3f = SO3< float >
 
template<class Scalar , int M, int Options = 0>
using Vector = Eigen::Matrix< Scalar, M, 1, Options >
 
template<class Scalar , int Options = 0>
using Vector2 = Vector< Scalar, 2, Options >
 
using Vector2d = Vector2< double >
 
using Vector2f = Vector2< float >
 
template<class Scalar , int Options = 0>
using Vector3 = Vector< Scalar, 3, Options >
 
using Vector3d = Vector3< double >
 
using Vector3f = Vector3< float >
 
template<class Scalar >
using Vector4 = Vector< Scalar, 4 >
 
using Vector4d = Vector4< double >
 
using Vector4f = Vector4< float >
 
template<class Scalar >
using Vector6 = Vector< Scalar, 6 >
 
using Vector6d = Vector6< double >
 
using Vector6f = Vector6< float >
 
template<class Scalar >
using Vector7 = Vector< Scalar, 7 >
 
using Vector7d = Vector7< double >
 
using Vector7f = Vector7< float >
 

Functions

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, SO2< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, RxSO2< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, SO3< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, RxSO3< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
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)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, Sim2< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar, int max_num_iterations=20)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, SE3< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar, int max_num_iterations=20)
 
template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same< typename SequenceContainer::value_type, Sim3< Scalar > >::value, optional< typename SequenceContainer::value_type > > average (SequenceContainer const &foo_Ts_bar, int max_num_iterations=20)
 
template<class Scalar , class Fn >
auto curveNumDiff (Fn curve, Scalar t, Scalar h=Constants< Scalar >::epsilonSqrt()) -> decltype(details::Curve< Scalar >::num_diff(std::move(curve), t, h))
 
template<class... Args>
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)
 
template<class T >
std::vector< SE2< T >, Eigen::aligned_allocator< SE2< T > > > getTestSE2s ()
 
template<class Scalar >
std::vector< SE3< Scalar >, Eigen::aligned_allocator< SE3< Scalar > > > getTestSE3s ()
 
template<class G , class Scalar2 = typename G::Scalar>
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))
 
template<class D >
SOPHUS_FUNC bool isOrthogonal (Eigen::MatrixBase< D > const &R)
 
template<class D >
SOPHUS_FUNC bool isScaledOrthogonalAndPositive (Eigen::MatrixBase< D > const &sR)
 
template<class SequenceContainer >
optional< typename SequenceContainer::value_type > iterativeMean (SequenceContainer const &foo_Ts_bar, int max_num_iterations)
 
template<class T >
Line2< T > lineFromSE2 (SE2< T > const &T_foo_line)
 
template<class T , int N>
Eigen::Hyperplane< T, N > makeHyperplaneUnique (Eigen::Hyperplane< T, N > const &plane)
 
template<class D >
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)
 
template<class T >
auto maxMetric (T const &p0, T const &p1) -> decltype(details::MaxMetric< T >::impl(p0, p1))
 
template<class T >
Vector2< T > normalFromSO2 (SO2< T > const &R_foo_line)
 
template<class T >
Vector3< T > normalFromSO3 (SO3< T > const &R_foo_plane)
 
template<class T >
Plane3< T > planeFromSE3 (SE3< T > const &T_foo_plane)
 
void processTestResult (bool passed)
 
template<class T >
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)))
 
template<class T >
SE2< T > SE2FromLine (Line2< T > const &line_foo)
 
template<class T >
SE3< T > SE3FromPlane (Plane3< T > const &plane_foo)
 
template<class T , class Scalar >
void setElementAt (T &p, Scalar value, int i)
 
template<class T >
void setToZero (T &p)
 
template<class T >
SO2< T > SO2FromNormal (Vector2< T > normal_foo)
 
template<class T >
SO3< T > SO3FromNormal (Vector3< T > const &normal_foo)
 
template<class T >
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 ()
 
template<class T >
auto transpose (T const &p) -> decltype(details::Transpose< T >::impl(T()))
 
template<class Scalar , int N, int M, class ScalarOrVector , class Fn >
Eigen::Matrix< Scalar, N, M > vectorFieldNumDiff (Fn vector_field, ScalarOrVector const &a, Scalar eps=Constants< Scalar >::epsilonSqrt())
 

Variables

constexpr nullopt_t nullopt {}
 

Typedef Documentation

◆ enable_if_t

template<bool B, class T = void>
using Sophus::enable_if_t = typedef typename std::enable_if<B, T>::type

Definition at line 221 of file common.hpp.

◆ Line2

template<class T >
using Sophus::Line2 = typedef Eigen::Hyperplane<T, 2>

Lines in 2d are hyperplanes.

Definition at line 235 of file types.hpp.

◆ Line2d

using Sophus::Line2d = typedef Line2<double>

Definition at line 236 of file types.hpp.

◆ Line2f

using Sophus::Line2f = typedef Line2<float>

Definition at line 237 of file types.hpp.

◆ Matrix

template<class Scalar , int M, int N>
using Sophus::Matrix = typedef Eigen::Matrix<Scalar, M, N>

Definition at line 41 of file types.hpp.

◆ Matrix2

template<class Scalar >
using Sophus::Matrix2 = typedef Matrix<Scalar, 2, 2>

Definition at line 44 of file types.hpp.

◆ Matrix2d

using Sophus::Matrix2d = typedef Matrix2<double>

Definition at line 46 of file types.hpp.

◆ Matrix2f

using Sophus::Matrix2f = typedef Matrix2<float>

Definition at line 45 of file types.hpp.

◆ Matrix3

template<class Scalar >
using Sophus::Matrix3 = typedef Matrix<Scalar, 3, 3>

Definition at line 49 of file types.hpp.

◆ Matrix3d

using Sophus::Matrix3d = typedef Matrix3<double>

Definition at line 51 of file types.hpp.

◆ Matrix3f

using Sophus::Matrix3f = typedef Matrix3<float>

Definition at line 50 of file types.hpp.

◆ Matrix4

template<class Scalar >
using Sophus::Matrix4 = typedef Matrix<Scalar, 4, 4>

Definition at line 54 of file types.hpp.

◆ Matrix4d

using Sophus::Matrix4d = typedef Matrix4<double>

Definition at line 56 of file types.hpp.

◆ Matrix4f

using Sophus::Matrix4f = typedef Matrix4<float>

Definition at line 55 of file types.hpp.

◆ Matrix6

template<class Scalar >
using Sophus::Matrix6 = typedef Matrix<Scalar, 6, 6>

Definition at line 59 of file types.hpp.

◆ Matrix6d

using Sophus::Matrix6d = typedef Matrix6<double>

Definition at line 61 of file types.hpp.

◆ Matrix6f

using Sophus::Matrix6f = typedef Matrix6<float>

Definition at line 60 of file types.hpp.

◆ Matrix7

template<class Scalar >
using Sophus::Matrix7 = typedef Matrix<Scalar, 7, 7>

Definition at line 64 of file types.hpp.

◆ Matrix7d

using Sophus::Matrix7d = typedef Matrix7<double>

Definition at line 66 of file types.hpp.

◆ Matrix7f

using Sophus::Matrix7f = typedef Matrix7<float>

Definition at line 65 of file types.hpp.

◆ ParametrizedLine

template<class Scalar , int N, int Options = 0>
using Sophus::ParametrizedLine = typedef Eigen::ParametrizedLine<Scalar, N, Options>

Definition at line 69 of file types.hpp.

◆ ParametrizedLine2

template<class Scalar , int Options = 0>
using Sophus::ParametrizedLine2 = typedef ParametrizedLine<Scalar, 2, Options>

Definition at line 77 of file types.hpp.

◆ ParametrizedLine2d

Definition at line 79 of file types.hpp.

◆ ParametrizedLine2f

Definition at line 78 of file types.hpp.

◆ ParametrizedLine3

template<class Scalar , int Options = 0>
using Sophus::ParametrizedLine3 = typedef ParametrizedLine<Scalar, 3, Options>

Definition at line 72 of file types.hpp.

◆ ParametrizedLine3d

Definition at line 74 of file types.hpp.

◆ ParametrizedLine3f

Definition at line 73 of file types.hpp.

◆ Plane3

template<class T >
using Sophus::Plane3 = typedef Eigen::Hyperplane<T, 3>

Planes in 3d are hyperplanes.

Definition at line 229 of file types.hpp.

◆ Plane3d

using Sophus::Plane3d = typedef Plane3<double>

Definition at line 230 of file types.hpp.

◆ Plane3f

using Sophus::Plane3f = typedef Plane3<float>

Definition at line 231 of file types.hpp.

◆ RxSO2d

using Sophus::RxSO2d = typedef RxSO2<double>

Definition at line 12 of file rxso2.hpp.

◆ RxSO2f

using Sophus::RxSO2f = typedef RxSO2<float>

Definition at line 13 of file rxso2.hpp.

◆ RxSO3d

using Sophus::RxSO3d = typedef RxSO3<double>

Definition at line 12 of file rxso3.hpp.

◆ RxSO3f

using Sophus::RxSO3f = typedef RxSO3<float>

Definition at line 13 of file rxso3.hpp.

◆ SE2d

using Sophus::SE2d = typedef SE2<double>

Definition at line 12 of file se2.hpp.

◆ SE2f

using Sophus::SE2f = typedef SE2<float>

Definition at line 13 of file se2.hpp.

◆ SE3d

using Sophus::SE3d = typedef SE3<double>

Definition at line 12 of file se3.hpp.

◆ SE3f

using Sophus::SE3f = typedef SE3<float>

Definition at line 13 of file se3.hpp.

◆ Sim2d

using Sophus::Sim2d = typedef Sim2<double>

Definition at line 13 of file sim2.hpp.

◆ Sim2f

using Sophus::Sim2f = typedef Sim2<float>

Definition at line 14 of file sim2.hpp.

◆ Sim3d

using Sophus::Sim3d = typedef Sim3<double>

Definition at line 13 of file sim3.hpp.

◆ Sim3f

using Sophus::Sim3f = typedef Sim3<float>

Definition at line 14 of file sim3.hpp.

◆ SO2d

using Sophus::SO2d = typedef SO2<double>

Definition at line 20 of file so2.hpp.

◆ SO2f

using Sophus::SO2f = typedef SO2<float>

Definition at line 21 of file so2.hpp.

◆ SO3d

using Sophus::SO3d = typedef SO3<double>

Definition at line 20 of file so3.hpp.

◆ SO3f

using Sophus::SO3f = typedef SO3<float>

Definition at line 21 of file so3.hpp.

◆ Vector

template<class Scalar , int M, int Options = 0>
using Sophus::Vector = typedef Eigen::Matrix<Scalar, M, 1, Options>

Definition at line 13 of file types.hpp.

◆ Vector2

template<class Scalar , int Options = 0>
using Sophus::Vector2 = typedef Vector<Scalar, 2, Options>

Definition at line 16 of file types.hpp.

◆ Vector2d

using Sophus::Vector2d = typedef Vector2<double>

Definition at line 18 of file types.hpp.

◆ Vector2f

using Sophus::Vector2f = typedef Vector2<float>

Definition at line 17 of file types.hpp.

◆ Vector3

template<class Scalar , int Options = 0>
using Sophus::Vector3 = typedef Vector<Scalar, 3, Options>

Definition at line 21 of file types.hpp.

◆ Vector3d

using Sophus::Vector3d = typedef Vector3<double>

Definition at line 23 of file types.hpp.

◆ Vector3f

using Sophus::Vector3f = typedef Vector3<float>

Definition at line 22 of file types.hpp.

◆ Vector4

template<class Scalar >
using Sophus::Vector4 = typedef Vector<Scalar, 4>

Definition at line 26 of file types.hpp.

◆ Vector4d

using Sophus::Vector4d = typedef Vector4<double>

Definition at line 28 of file types.hpp.

◆ Vector4f

using Sophus::Vector4f = typedef Vector4<float>

Definition at line 27 of file types.hpp.

◆ Vector6

template<class Scalar >
using Sophus::Vector6 = typedef Vector<Scalar, 6>

Definition at line 31 of file types.hpp.

◆ Vector6d

using Sophus::Vector6d = typedef Vector6<double>

Definition at line 33 of file types.hpp.

◆ Vector6f

using Sophus::Vector6f = typedef Vector6<float>

Definition at line 32 of file types.hpp.

◆ Vector7

template<class Scalar >
using Sophus::Vector7 = typedef Vector<Scalar, 7>

Definition at line 36 of file types.hpp.

◆ Vector7d

using Sophus::Vector7d = typedef Vector7<double>

Definition at line 38 of file types.hpp.

◆ Vector7f

using Sophus::Vector7f = typedef Vector7<float>

Definition at line 37 of file types.hpp.

Function Documentation

◆ average() [1/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, SO2<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar)

Definition at line 70 of file average.hpp.

◆ average() [2/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, RxSO2<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar)

Definition at line 91 of file average.hpp.

◆ average() [3/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, SO3<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar)

Definition at line 165 of file average.hpp.

◆ average() [4/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, RxSO3<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar)

Definition at line 175 of file average.hpp.

◆ average() [5/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, SE2<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar,
int  max_num_iterations = 20 
)

Definition at line 194 of file average.hpp.

◆ average() [6/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, Sim2<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar,
int  max_num_iterations = 20 
)

Definition at line 205 of file average.hpp.

◆ average() [7/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, SE3<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar,
int  max_num_iterations = 20 
)

Definition at line 214 of file average.hpp.

◆ average() [8/8]

template<class SequenceContainer , class Scalar = typename SequenceContainer::value_type::Scalar>
enable_if_t< std::is_same<typename SequenceContainer::value_type, Sim3<Scalar> >::value, optional<typename SequenceContainer::value_type> > Sophus::average ( SequenceContainer const &  foo_Ts_bar,
int  max_num_iterations = 20 
)

Definition at line 223 of file average.hpp.

◆ curveNumDiff()

template<class Scalar , class Fn >
auto Sophus::curveNumDiff ( Fn  curve,
Scalar  t,
Scalar  h = Constants<Scalar>::epsilonSqrt() 
) -> decltype(details::Curve<Scalar>::num_diff(std::move(curve), t, h))

Calculates the derivative of a curve at a point t.

Here, a curve is a function from a Scalar to a Euclidean space. Thus, it returns either a Scalar, a vector or a matrix.

Definition at line 72 of file num_diff.hpp.

◆ defaultEnsure()

template<class... Args>
SOPHUS_FUNC void Sophus::defaultEnsure ( char const *  function,
char const *  file,
int  line,
char const *  description,
Args &&...  args 
)

Definition at line 122 of file common.hpp.

◆ ensureFailed()

void Sophus::ensureFailed ( char const *  function,
char const *  file,
int  line,
char const *  description 
)

Definition at line 7 of file example_ensure_handler.cpp.

◆ getTestSE2s()

template<class T >
std::vector<SE2<T>, Eigen::aligned_allocator<SE2<T> > > Sophus::getTestSE2s ( )

Definition at line 547 of file tests.hpp.

◆ getTestSE3s()

template<class Scalar >
std::vector<SE3<Scalar>, Eigen::aligned_allocator<SE3<Scalar> > > Sophus::getTestSE3s ( )

Definition at line 508 of file tests.hpp.

◆ interpolate()

template<class G , class Scalar2 = typename G::Scalar>
enable_if_t<interp_details::Traits<G>::supported, G> Sophus::interpolate ( G const &  foo_T_bar,
G const &  foo_T_baz,
Scalar2  p = Scalar2(0.5f) 
)

This function interpolates between two Lie group elements foo_T_bar and foo_T_baz with an interpolation factor of alpha in [0, 1].

It returns a pose foo_T_quiz with quiz being a frame between bar and baz. If alpha=0 it returns foo_T_bar. If it is 1, it returns foo_T_bar.

(Since interpolation on Lie groups is inverse-invariant, we can equivalently think of the input arguments as being bar_T_foo, baz_T_foo and the return value being quiz_T_foo.)

Precondition: p must be in [0, 1].

Definition at line 27 of file interpolate.hpp.

◆ isOrthogonal()

template<class D >
SOPHUS_FUNC bool Sophus::isOrthogonal ( Eigen::MatrixBase< D > const &  R)

Takes in arbitrary square matrix and returns true if it is orthogonal.

Definition at line 17 of file rotation_matrix.hpp.

◆ isScaledOrthogonalAndPositive()

template<class D >
SOPHUS_FUNC bool Sophus::isScaledOrthogonalAndPositive ( Eigen::MatrixBase< D > const &  sR)

Takes in arbitrary square matrix and returns true if it is "scaled-orthogonal" with positive determinant.

Definition at line 33 of file rotation_matrix.hpp.

◆ iterativeMean()

template<class SequenceContainer >
optional<typename SequenceContainer::value_type> Sophus::iterativeMean ( SequenceContainer const &  foo_Ts_bar,
int  max_num_iterations 
)

Calculates mean iteratively.

Returns nullopt if it does not converge.

Definition at line 24 of file average.hpp.

◆ lineFromSE2()

template<class T >
Line2<T> Sophus::lineFromSE2 ( SE2< T > const &  T_foo_line)

Returns a line (wrt. to frame foo), given a pose of the line in reference frame foo.

Note: The plane is defined by X-axis of the line frame.

Definition at line 126 of file geometry.hpp.

◆ makeHyperplaneUnique()

template<class T , int N>
Eigen::Hyperplane<T, N> Sophus::makeHyperplaneUnique ( Eigen::Hyperplane< T, N > const &  plane)

Takes in a hyperplane and returns unique representation by ensuring that the offset is not negative.

Definition at line 168 of file geometry.hpp.

◆ makeRotationMatrix()

template<class D >
SOPHUS_FUNC enable_if_t< std::is_floating_point<typename D::Scalar>::value, Matrix<typename D::Scalar, D::RowsAtCompileTime, D::RowsAtCompileTime> > Sophus::makeRotationMatrix ( Eigen::MatrixBase< D > const &  R)

Takes in arbitrary square matrix (2x2 or larger) and returns closest orthogonal matrix with positive determinant.

Definition at line 62 of file rotation_matrix.hpp.

◆ maxMetric()

template<class T >
auto Sophus::maxMetric ( T const &  p0,
T const &  p1 
) -> decltype(details::MaxMetric<T>::impl(p0, p1))

Returns maximum metric between two points p0 and p1, with p0, p1 being matrices or a scalars.

Definition at line 164 of file types.hpp.

◆ normalFromSO2()

template<class T >
Vector2<T> Sophus::normalFromSO2 ( SO2< T > const &  R_foo_line)

Takes in a rotation R_foo_plane and returns the corresponding line normal along the y-axis (in reference frame foo).

Definition at line 19 of file geometry.hpp.

◆ normalFromSO3()

template<class T >
Vector3<T> Sophus::normalFromSO3 ( SO3< T > const &  R_foo_plane)

Takes in a rotation R_foo_plane and returns the corresponding plane normal along the z-axis (in reference frame foo).

Definition at line 41 of file geometry.hpp.

◆ planeFromSE3()

template<class T >
Plane3<T> Sophus::planeFromSE3 ( SE3< T > const &  T_foo_plane)

Returns a plane (wrt. to frame foo), given a pose of the plane in reference frame foo.

Note: The plane is defined by XY-plane of the frame plane.

Definition at line 148 of file geometry.hpp.

◆ processTestResult()

void Sophus::processTestResult ( bool  passed)

Definition at line 38 of file test_macros.hpp.

◆ rotationFromNormal()

template<class T >
Matrix3<T> Sophus::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)) 
)

Takes in plane normal in reference frame foo and constructs a corresponding rotation matrix R_foo_plane.

Note: The plane frame is defined as such that the normal points along the positive z-axis. One can specify hints for the x-axis and y-axis of the plane frame.

Preconditions:

  • normal_foo, xDirHint_foo, yDirHint_foo must not be close to zero.
  • xDirHint_foo and yDirHint_foo must be approx. perpendicular.

Definition at line 58 of file geometry.hpp.

◆ SE2FromLine()

template<class T >
SE2<T> Sophus::SE2FromLine ( Line2< T > const &  line_foo)

Returns the pose T_foo_line, given a line in reference frame foo.

Note: The line is defined by X-axis of the frame line.

Definition at line 135 of file geometry.hpp.

◆ SE3FromPlane()

template<class T >
SE3<T> Sophus::SE3FromPlane ( Plane3< T > const &  plane_foo)

Returns the pose T_foo_plane, given a plane in reference frame foo.

Note: The plane is defined by XY-plane of the frame plane.

Definition at line 157 of file geometry.hpp.

◆ setElementAt()

template<class T , class Scalar >
void Sophus::setElementAt ( T &  p,
Scalar  value,
int  i 
)

Sets ith component of p to value, with p being a matrix or a scalar. If p is a scalar, i must be 0.

Definition at line 180 of file types.hpp.

◆ setToZero()

template<class T >
void Sophus::setToZero ( T &  p)

Sets point p to zero, with p being a matrix or a scalar.

Definition at line 172 of file types.hpp.

◆ SO2FromNormal()

template<class T >
SO2<T> Sophus::SO2FromNormal ( Vector2< T >  normal_foo)

Takes in line normal in reference frame foo and constructs a corresponding rotation matrix R_foo_line.

Precondition: normal_foo must not be close to zero.

Definition at line 29 of file geometry.hpp.

◆ SO3FromNormal()

template<class T >
SO3<T> Sophus::SO3FromNormal ( Vector3< T > const &  normal_foo)

Takes in plane normal in reference frame foo and constructs a corresponding rotation matrix R_foo_plane.

See rotationFromNormal for details.

Definition at line 116 of file geometry.hpp.

◆ squaredNorm()

template<class T >
auto Sophus::squaredNorm ( T const &  p) -> decltype(details::SquaredNorm<T>::impl(p))

Returns the squared 2-norm of p, with p being a vector or a scalar.

Definition at line 187 of file types.hpp.

◆ test_rxso2()

int Sophus::test_rxso2 ( )

Definition at line 200 of file test_rxso2.cpp.

◆ test_rxso3()

int Sophus::test_rxso3 ( )

Definition at line 220 of file test_rxso3.cpp.

◆ test_se2()

int Sophus::test_se2 ( )

Definition at line 214 of file test_se2.cpp.

◆ test_se3()

int Sophus::test_se3 ( )

Definition at line 225 of file test_se3.cpp.

◆ test_sim3()

int Sophus::test_sim3 ( )

Definition at line 184 of file test_sim2.cpp.

◆ test_so2()

int Sophus::test_so2 ( )

Definition at line 153 of file test_so2.cpp.

◆ test_so3()

int Sophus::test_so3 ( )

Definition at line 195 of file test_so3.cpp.

◆ transpose()

template<class T >
auto Sophus::transpose ( T const &  p) -> decltype(details::Transpose<T>::impl(T()))

Returns p.transpose() if p is a matrix, and simply p if m is a scalar.

Definition at line 195 of file types.hpp.

◆ vectorFieldNumDiff()

template<class Scalar , int N, int M, class ScalarOrVector , class Fn >
Eigen::Matrix<Scalar, N, M> Sophus::vectorFieldNumDiff ( Fn  vector_field,
ScalarOrVector const &  a,
Scalar  eps = Constants<Scalar>::epsilonSqrt() 
)

Calculates the derivative of a vector field at a point a.

Here, a vector field is a function from a vector space to another vector space.

Definition at line 84 of file num_diff.hpp.

Variable Documentation

◆ nullopt

constexpr nullopt_t Sophus::nullopt {}
constexpr

Definition at line 177 of file common.hpp.



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