38 orientation_ = addSubState<OrientationStateType::VectorDimension,OrientationStateType::CovarianceDimension>(
"orientation");
39 rate_ = addSubState<RateStateType::VectorDimension,RateStateType::CovarianceDimension>(
"rate");
40 position_ = addSubState<PositionStateType::VectorDimension,PositionStateType::CovarianceDimension>(
"position");
41 velocity_ = addSubState<VelocityStateType::VectorDimension,VelocityStateType::CovarianceDimension>(
"velocity");
49 orientation_ = addSubState<OrientationStateType::VectorDimension,OrientationStateType::CovarianceDimension>(
"orientation");
50 position_ = addSubState<PositionStateType::VectorDimension,PositionStateType::CovarianceDimension>(
"position");
51 velocity_ = addSubState<VelocityStateType::VectorDimension,VelocityStateType::CovarianceDimension>(
"velocity");
59 orientation_ = addSubState<OrientationStateType::VectorDimension,OrientationStateType::CovarianceDimension>(
"orientation");
67 position_ = addSubState<PositionStateType::VectorDimension,PositionStateType::CovarianceDimension>(
"position");
68 velocity_ = addSubState<VelocityStateType::VectorDimension,VelocityStateType::CovarianceDimension>(
"velocity");
125 R = q.toRotationMatrix();
142 return atan2(2*q.x()*q.y() + 2*q.w()*q.z(), q.x()*q.x() + q.w()*q.w() - q.z()*q.z() - q.y()*q.y());
148 roll = atan2(2*(q.y()*q.z() + q.w()*q.x()), q.w()*q.w() - q.x()*q.x() - q.y()*q.y() + q.z()*q.z());
149 pitch = -asin(2*(q.x()*q.z() - q.w()*q.y()));
150 yaw = atan2(2*(q.x()*q.y() + q.w()*q.z()), q.w()*q.w() + q.x()*q.x() - q.y()*q.y() - q.z()*q.z());
156 getEuler(euler(0), euler(1), euler(2));
164 int orientation_index, orientation_size;
166 orientation_index =
orientation()->getCovarianceIndex();
167 orientation_size =
orientation()->getCovarianceDimension();
170 orientation_index =
orientation()->getVectorIndex();
171 orientation_size =
orientation()->getVectorDimension();
175 if (orientation_index > 0) {
176 int length = orientation_index;
181 if (orientation_index + orientation_size < vector_update.size()) {
182 int length = vector_update.size() - orientation_index - orientation_size;
191 x() += vector_update;
204 Eigen::Quaterniond q(
orientation()->vector().data());
205 q = Eigen::Quaterniond().fromRotationVector(rotation_vector) * q;
220 if (!(*it)(new_status))
return false;
270 roll = atan2(2*(q.y()*q.z() + q.w()*q.x()), q.w()*q.w() - q.x()*q.x() - q.y()*q.y() + q.z()*q.z());
271 pitch = -asin(2*(q.x()*q.z() - q.w()*q.y()));
278 fake_orientation_ =
Quaternion(Eigen::AngleAxis<ScalarType>(yaw, ColumnVector3::UnitZ()) * Eigen::AngleAxis<ScalarType>(pitch, ColumnVector3::UnitY()) * Eigen::AngleAxis<ScalarType>(roll, ColumnVector3::UnitX())).coeffs();
284 double yaw = atan2(2*(q.x()*q.y() + q.w()*q.z()), q.w()*q.w() + q.x()*q.x() - q.y()*q.y() - q.z()*q.z());
291 fake_orientation_ =
Quaternion(Eigen::AngleAxis<ScalarType>(yaw, ColumnVector3::UnitZ()) * Eigen::AngleAxis<ScalarType>(euler(1), ColumnVector3::UnitY()) * Eigen::AngleAxis<ScalarType>(euler(2), ColumnVector3::UnitX())).coeffs();