libxr  1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
inertia.hpp
1#pragma once
2
3#ifndef LIBXR_NO_EIGEN
4
5#include <Eigen/Core>
6#include <Eigen/Dense>
7#include <type_traits>
8
9#include "transform.hpp"
10
11namespace LibXR
12{
13
14using DefaultScalar = LIBXR_DEFAULT_SCALAR;
15
23template <typename Scalar = DefaultScalar>
25{
26 public:
27 Scalar data[9];
29 Scalar mass;
30
39 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
40 std::is_same<T, float>::value ||
41 std::is_same<T, double>::value,
42 int> = 0>
43 explicit Inertia(Scalar m, const T (&values)[9]) : mass(m)
44 {
45 for (int i = 0; i < 3; i++)
46 {
47 for (int j = 0; j < 3; j++)
48 {
49 data[i * 3 + j] = static_cast<Scalar>(values[i * 3 + j]);
50 }
51 }
52 }
53
62 template <typename T, std::enable_if_t<std::is_same<T, Scalar>::value ||
63 std::is_same<T, float>::value ||
64 std::is_same<T, double>::value,
65 int> = 0>
66 explicit Inertia(Scalar m, const T (&matrix)[3][3]) : mass(m)
67 {
68 for (int i = 0; i < 3; i++)
69 {
70 for (int j = 0; j < 3; j++)
71 {
72 data[i * 3 + j] = static_cast<Scalar>(matrix[i][j]);
73 }
74 }
75 }
76
81 Inertia() : mass(0) { memset(data, 0, sizeof(data)); }
82
90 template <typename T,
91 std::enable_if_t<
92 std::is_same<T, float>::value || std::is_same<T, double>::value, int> = 0>
93 explicit Inertia(Scalar m, const T (&arr)[6])
94 : data{arr[0], -arr[3], -arr[5], -arr[3], arr[1],
95 -arr[4], -arr[5], -arr[4], arr[2]},
96 mass(m)
97 {
98 }
99
107 Inertia(Scalar m, Scalar xx, Scalar yy, Scalar zz, Scalar xy, Scalar yz, Scalar xz)
108 : data{xx, -xy, -xz, -xy, yy, -yz, -xz, -yz, zz}, mass(m)
109 {
110 }
111
118 Inertia(Scalar m, const Eigen::Matrix<Scalar, 3, 3> &R) : mass(m)
119 {
120 memcpy(data, R.data(), 9 * sizeof(Scalar));
121 }
122
124 operator Eigen::Matrix<Scalar, 3, 3>() const
125 {
126 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(data);
127 }
128
131 Scalar operator()(int i, int j) const { return data[i + j * 3]; }
132
135
136 Eigen::Matrix<Scalar, 3, 3> operator+(const Eigen::Matrix<Scalar, 3, 3> &R) const
137 {
138 return Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(data) + R;
139 }
140
146 Inertia Translate(const Eigen::Matrix<Scalar, 3, 1> &p) const
147 {
148 Scalar dx = p(0), dy = p(1), dz = p(2);
149 Eigen::Matrix<Scalar, 3, 3> translation_matrix;
150 translation_matrix << dy * dy + dz * dz, -dx * dy, -dx * dz, -dx * dy,
151 dx * dx + dz * dz, -dy * dz, -dx * dz, -dy * dz, dx * dx + dy * dy;
152
153 return Inertia(mass, Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(data) +
154 mass * translation_matrix);
155 }
156
162 Inertia Rotate(const Eigen::Matrix<Scalar, 3, 3> &R) const
163 {
164 return Inertia(
165 mass, R * Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(data) * R.transpose());
166 }
167
175 {
176 return Rotate(Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(R.data_));
177 }
178
184 Inertia Rotate(const Eigen::Quaternion<Scalar> &q) const
185 {
186 return Inertia(
187 mass, q * Eigen::Map<const Eigen::Matrix<Scalar, 3, 3>>(data) * q.conjugate());
188 }
189
196 static Eigen::Matrix<Scalar, 3, 3> Rotate(const Eigen::Matrix<Scalar, 3, 3> &R,
197 const Eigen::Quaternion<Scalar> &q)
198 {
199 return q * R * q.conjugate();
200 }
201
209 {
210 return Rotate(Eigen::Quaternion<Scalar>(q));
211 }
212};
213
219template <typename Scalar = DefaultScalar>
221{
222 public:
223 Eigen::Matrix<Scalar, 3, 1> position;
224 Scalar mass;
225
228 CenterOfMass() : position(0., 0., 0.), mass(0.) {}
229
236 CenterOfMass(Scalar m, const LibXR::Position<Scalar> &p) : position(p), mass(m) {}
237
244 CenterOfMass(Scalar m, const Eigen::Matrix<Scalar, 3, 1> &p) : position(p), mass(m) {}
245
253 : position(p.translation), mass(m.mass)
254 {
255 }
256
263 {
264 Scalar new_mass = mass + m.mass;
265 return CenterOfMass(
266 new_mass,
267 Position<Scalar>((position(0) * mass + m.position(0) * m.mass) / new_mass,
268 (position(1) * mass + m.position(1) * m.mass) / new_mass,
269 (position(2) * mass + m.position(2) * m.mass) / new_mass));
270 }
271
278 {
279 *this = *this + m;
280 return *this;
281 }
282};
283
284} // namespace LibXR
285
286#endif
质心信息表示类。Represents the center of mass information.
Definition inertia.hpp:221
CenterOfMass()
默认构造函数,初始化质心位置为 (0,0,0),质量为 0。Default constructor initializing position to (0,0,0) and mass to 0.
Definition inertia.hpp:228
CenterOfMass(Scalar m, const Eigen::Matrix< Scalar, 3, 1 > &p)
使用质量和 Eigen 3D 向量构造质心对象。Constructs a center of mass object using mass and Eigen 3D vector.
Definition inertia.hpp:244
Eigen::Matrix< Scalar, 3, 1 > position
质心位置。Center of mass position.
Definition inertia.hpp:223
CenterOfMass & operator+=(const CenterOfMass &m)
质心累加运算符。Accumulation operator for center of mass.
Definition inertia.hpp:277
CenterOfMass(const Inertia< Scalar > &m, const Transform< Scalar > &p)
从惯性对象和变换构造质心对象。Constructs a center of mass object from inertia and transformation.
Definition inertia.hpp:252
CenterOfMass(Scalar m, const LibXR::Position< Scalar > &p)
使用质量和位置构造质心对象。Constructs a center of mass object using mass and position.
Definition inertia.hpp:236
Scalar mass
质量值。Mass value.
Definition inertia.hpp:224
CenterOfMass operator+(const CenterOfMass &m) const
计算两个质心的合成。Computes the combined center of mass.
Definition inertia.hpp:262
表示刚体的惯性张量和质量信息的类。Provides a class to represent the inertia tensor and mass of a rigid body.
Definition inertia.hpp:25
Inertia(Scalar m, const T(&values)[9])
使用质量和 3x3 惯性张量数组构造惯性对象。Constructs an inertia object using mass and a 3x3 inertia tensor array.
Definition inertia.hpp:43
Inertia(Scalar m, Scalar xx, Scalar yy, Scalar zz, Scalar xy, Scalar yz, Scalar xz)
直接指定质量和惯性张量分量构造惯性对象。Constructs an inertia object with mass and specified inertia tensor elements.
Definition inertia.hpp:107
Inertia Rotate(const Quaternion< Scalar > &q) const
使用自定义 Quaternion 旋转惯性张量。Rotates the inertia tensor using a custom Quaternion.
Definition inertia.hpp:208
static Eigen::Matrix< Scalar, 3, 3 > Rotate(const Eigen::Matrix< Scalar, 3, 3 > &R, const Eigen::Quaternion< Scalar > &q)
使用四元数旋转 3x3 矩阵。Rotates a 3x3 matrix using a quaternion.
Definition inertia.hpp:196
Scalar mass
质量值。Mass value.
Definition inertia.hpp:29
Scalar data[9]
Definition inertia.hpp:27
Inertia Rotate(const RotationMatrix< Scalar > &R) const
使用 RotationMatrix 旋转惯性张量。Rotates the inertia tensor using a RotationMatrix.
Definition inertia.hpp:174
Inertia(Scalar m, const T(&matrix)[3][3])
使用质量和二维 3x3 数组构造惯性对象。Constructs an inertia object using mass and a 3x3 matrix.
Definition inertia.hpp:66
Inertia()
默认构造函数,初始化质量为0,惯性张量为零矩阵。Default constructor initializing mass to 0 and inertia tensor to zero.
Definition inertia.hpp:81
Inertia(Scalar m, const T(&arr)[6])
使用质量和 6 维数组(对称惯性矩阵)构造惯性对象。Constructs an inertia object using mass and a 6-element symmetric inertia m...
Definition inertia.hpp:93
Inertia Rotate(const Eigen::Quaternion< Scalar > &q) const
使用四元数旋转惯性张量。Rotates the inertia tensor using a quaternion.
Definition inertia.hpp:184
Scalar operator()(int i, int j) const
获取惯性张量中的特定元素。Retrieves a specific element from the inertia tensor.
Definition inertia.hpp:131
Inertia Rotate(const Eigen::Matrix< Scalar, 3, 3 > &R) const
旋转惯性张量。Rotates the inertia tensor.
Definition inertia.hpp:162
Inertia Translate(const Eigen::Matrix< Scalar, 3, 1 > &p) const
平移惯性对象。Translates the inertia object.
Definition inertia.hpp:146
Eigen::Matrix< Scalar, 3, 3 > operator+(const Eigen::Matrix< Scalar, 3, 3 > &R) const
将惯性张量与另一个 3x3 矩阵相加。Adds the inertia tensor with another 3x3 matrix.
Definition inertia.hpp:136
Inertia(Scalar m, const Eigen::Matrix< Scalar, 3, 3 > &R)
使用 Eigen 3x3 矩阵构造惯性对象。Constructs an inertia object using an Eigen 3x3 matrix.
Definition inertia.hpp:118
三维空间中的位置向量 / 3D position vector
Definition transform.hpp:39
四元数表示与运算,继承自 Eigen::Quaternion / Quaternion representation and operations, inheriting from Eigen::Qua...
旋转矩阵类,继承自 Eigen::Matrix<Scalar, 3, 3>。 Rotation matrix class, inheriting from Eigen::Matrix<Scalar,...
表示三维空间中的刚体变换,包括旋转和位移。Represents rigid body transformations in 3D space, including rotation and transl...
LibXR 命名空间
Definition ch32_gpio.hpp:9