30 #include "Eigen/src/Core/GlobalFunctions.h"
31 #include "Eigen/src/Core/Matrix.h"
32 #include "Eigen/src/Core/util/Constants.h"
33 #include "Eigen/src/Geometry/Quaternion.h"
34 #include <Eigen/Dense>
53 state.
p = Eigen::Vector3d(
s.position[0],
s.position[1],
s.position[2]);
54 state.
q = Eigen::Quaterniond(
s.position[3],
s.position[4],
s.position[5],
s.position[6]).normalized();
56 state.
v = Eigen::Vector3d::Zero();
57 state.
w = Eigen::Vector3d::Zero();
58 state.
v_dot = Eigen::Vector3d::Zero();
59 state.
w_dot = Eigen::Vector3d::Zero();
78 auto fill = [](
auto& vec,
const auto& first,
const auto& second) {
79 vec.push_back(first.x());
80 vec.push_back(first.y());
81 vec.push_back(first.z());
83 vec.push_back(second.w());
84 vec.push_back(second.x());
85 vec.push_back(second.y());
86 vec.push_back(second.z());
93 if (std::isnan(state.
v.x()) || std::isnan(state.
v.y()) || std::isnan(state.
v.z()) || std::isnan(state.
w.x()) ||
94 std::isnan(state.
w.y()) || std::isnan(state.
w.z()))
98 Eigen::Quaterniond q_dot;
99 Eigen::Vector3d tmp = state.
q.inverse() * state.
w;
100 Eigen::Quaterniond omega(0, tmp.x(), tmp.y(), tmp.z());
102 q_dot.coeffs() = 0.5 * (state.
q * omega).coeffs();
104 fill(spline_state.
velocity, state.
q.inverse() * state.
v, q_dot);
107 if (std::isnan(state.
v_dot.x()) || std::isnan(state.
v_dot.y()) || std::isnan(state.
v_dot.z()) ||
108 std::isnan(state.
w_dot.x()) || std::isnan(state.
w_dot.y()) || std::isnan(state.
w_dot.z()))
112 Eigen::Quaterniond q_ddot;
113 tmp = state.
q.inverse() * state.
w_dot;
114 Eigen::Quaterniond omega_dot(0, tmp.x(), tmp.y(), tmp.z());
116 q_ddot.coeffs() = 0.5 * (state.
q * omega_dot).coeffs() + 0.5 * (q_dot * omega).coeffs();
132 if (
s.position.empty())
136 state.
p = Eigen::Vector3d(
s.position[0],
s.position[1],
s.position[2]);
137 state.
q = Eigen::Quaterniond(
s.position[3],
s.position[4],
s.position[5],
s.position[6]).normalized();
140 if (
s.velocity.empty())
144 Eigen::Quaterniond q_dot(
s.velocity[3],
s.velocity[4],
s.velocity[5],
s.velocity[6]);
147 Eigen::Quaterniond omega;
148 omega.coeffs() = 2.0 * (state.
q.inverse() * q_dot).coeffs();
150 state.
v = Eigen::Vector3d(
s.velocity[0],
s.velocity[1],
s.velocity[2]);
151 state.
w = Eigen::Vector3d(omega.x(), omega.y(), omega.z());
154 if (
s.acceleration.empty())
157 state.
v = state.
q * state.
v;
158 state.
w = state.
q * state.
w;
161 Eigen::Quaterniond q_ddot(
s.acceleration[3],
s.acceleration[4],
s.acceleration[5],
s.acceleration[6]);
164 Eigen::Quaterniond omega_dot;
165 omega_dot.coeffs() = 2.0 * ((state.
q.inverse() * q_ddot).coeffs() -
166 ((state.
q.inverse() * q_dot) * (state.
q.inverse() * q_dot)).coeffs());
168 state.
v_dot = Eigen::Vector3d(
s.acceleration[0],
s.acceleration[1],
s.acceleration[2]);
169 state.
w_dot = Eigen::Vector3d(omega_dot.x(), omega_dot.y(), omega_dot.z());
172 state.
v = state.
q * state.
v;
173 state.
w = state.
q * state.
w;
183 for (
size_t i = 0; i < state.
position.size(); ++i)
188 for (
size_t i = 0; i < state.
velocity.size(); ++i)