Go to the documentation of this file.
22 #ifndef OV_TYPE_TYPE_JPLQUAT_H
23 #define OV_TYPE_TYPE_JPLQUAT_H
96 Eigen::Vector4d q0 = Eigen::Vector4d::Zero();
114 void update(
const Eigen::VectorXd &dx)
override {
116 assert(dx.rows() ==
_size);
119 Eigen::Matrix<double, 4, 1> dq;
139 std::shared_ptr<Type>
clone()
override {
140 auto Clone = std::shared_ptr<JPLQuat>(
new JPLQuat());
141 Clone->set_value(
value());
142 Clone->set_fej(
fej());
147 Eigen::Matrix<double, 3, 3>
Rot()
const {
return _R; }
154 Eigen::Matrix<double, 3, 3>
_R;
165 assert(new_value.rows() == 4);
166 assert(new_value.cols() == 1);
180 assert(new_value.rows() == 4);
181 assert(new_value.cols() == 1);
192 #endif // OV_TYPE_TYPE_JPLQUAT_H
Eigen::Matrix< double, 3, 3 > _Rfej
int _size
Dimension of error state.
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
Multiply two JPL quaternions.
std::shared_ptr< Type > clone() override
Create a clone of this variable.
Eigen::Matrix< double, 3, 3 > _R
Eigen::Matrix< double, 3, 3 > Rot() const
Rotation access.
virtual const Eigen::MatrixXd & value() const
Access variable's estimate.
void update(const Eigen::VectorXd &dx) override
Implements update operation by left-multiplying the current quaternion with a quaternion built from a...
Derived Type class that implements JPL quaternion.
Eigen::Matrix< double, 3, 3 > Rot_fej() const
FEJ Rotation access.
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
Converts JPL quaterion to SO(3) rotation matrix.
void set_value_internal(const Eigen::MatrixXd &new_value)
Sets the value of the estimate and recomputes the internal rotation matrix.
void set_fej_internal(const Eigen::MatrixXd &new_value)
Sets the fej value and recomputes the fej rotation matrix.
void set_value(const Eigen::MatrixXd &new_value) override
Sets the value of the estimate and recomputes the internal rotation matrix.
Dynamic type system types.
Eigen::Matrix< double, 4, 1 > quatnorm(Eigen::Matrix< double, 4, 1 > q_t)
Normalizes a quaternion to make sure it is unit norm.
virtual const Eigen::MatrixXd & fej() const
Access variable's first-estimate.
Eigen::MatrixXd _fej
First-estimate.
Eigen::MatrixXd _value
Current best estimate.
void set_fej(const Eigen::MatrixXd &new_value) override
Sets the fej value and recomputes the fej rotation matrix.
Base class for estimated variables.
ov_core
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17