template<typename _Scalar>
manif::SGal3 struct

Represent an element of SGal3.

Base classes

template<typename _Derived>
struct SGal3Base<SGal3<_Scalar>>
The base class of the SGal3 group.

Public types

using Translation = typename Base::Translation
using Quaternion = Eigen::Quaternion<Scalar>
using LinearVelocity = typename Base::LinearVelocity

Constructors, destructors, conversion operators

SGal3() defaulted
~SGal3() defaulted
template<typename _DerivedOther>
SGal3(const LieGroupBase<_DerivedOther>& o)
SGal3(const Translation& t, const Eigen::Quaternion<Scalar>& q, const LinearVelocity& v, const Scalar time)
Constructor given a translation, a unit quaternion and a linear velocity.
SGal3(const Translation& t, const Eigen::AngleAxis<Scalar>& angle_axis, const LinearVelocity& v, const Scalar time)
Constructor given a translation, an angle axis and a linear velocity.
SGal3(const Translation& t, const SO3<Scalar>& SO3, const LinearVelocity& v, const Scalar time)
Constructor given a translation, SO3 element and a linear velocity.
SGal3(const Scalar x, const Scalar y, const Scalar z, const Scalar roll, const Scalar pitch, const Scalar yaw, const Scalar vx, const Scalar vy, const Scalar vz, const Scalar t)
Constructor given translation components, roll-pitch-yaw angles and linear velocity components.
SGal3(const Eigen::Transform<_Scalar, 3, Eigen::Isometry>& h, const LinearVelocity& v, const Scalar t)
Constructor from a 3D Eigen::Isometry<Scalar> relevant to SE(3) and a linear velocity.

Public functions

auto coeffs() -> DataType&
auto coeffs() const -> const DataType&

Protected variables

DataType data_

Function documentation

template<typename _Scalar>
manif::SGal3<_Scalar>::SGal3(const Translation& t, const Eigen::Quaternion<Scalar>& q, const LinearVelocity& v, const Scalar time)

Constructor given a translation, a unit quaternion and a linear velocity.

Parameters
in A translation vector.
in A unit quaternion.
in A linear velocity vector.
time in A time.
Exceptions
manif::invalid_argument on un-normalized complex number.

template<typename _Scalar>
manif::SGal3<_Scalar>::SGal3(const Translation& t, const Eigen::AngleAxis<Scalar>& angle_axis, const LinearVelocity& v, const Scalar time)

Constructor given a translation, an angle axis and a linear velocity.

Parameters
in A translation vector.
angle_axis in An angle-axis.
in A linear velocity vector.
time in A time.

template<typename _Scalar>
manif::SGal3<_Scalar>::SGal3(const Translation& t, const SO3<Scalar>& SO3, const LinearVelocity& v, const Scalar time)

Constructor given a translation, SO3 element and a linear velocity.

Parameters
in A translation vector.
SO3
in A linear velocity vector.
time in A time.

template<typename _Scalar>
manif::SGal3<_Scalar>::SGal3(const Scalar x, const Scalar y, const Scalar z, const Scalar roll, const Scalar pitch, const Scalar yaw, const Scalar vx, const Scalar vy, const Scalar vz, const Scalar t)

Constructor given translation components, roll-pitch-yaw angles and linear velocity components.

Parameters
in The x component of the translation.
in The y component of the translation.
in The z component of the translation.
roll in The roll angle.
pitch in The pitch angle.
yaw in The yaw angle.
vx in The x component of the linear velocity.
vy in The y component of the linear velocity.
vz in The z component of the linear velocity.
in time.

template<typename _Scalar>
manif::SGal3<_Scalar>::SGal3(const Eigen::Transform<_Scalar, 3, Eigen::Isometry>& h, const LinearVelocity& v, const Scalar t)

Constructor from a 3D Eigen::Isometry<Scalar> relevant to SE(3) and a linear velocity.

Parameters
in a isometry object from Eigen defined for SE(3)
in a linear velocity vector.
t