FancySafeBot 0.0.1
A safe robotics library
Loading...
Searching...
No Matches
fsb_rotation.h
1
2#ifndef FSB_ROTATION_H
3#define FSB_ROTATION_H
4
5#include "fsb_quaternion.h"
6#include "fsb_types.h"
7
8namespace fsb
9{
10
26Mat3 skew_symmetric(const Vec3& vec);
27
34Vec3 quat_to_ezyx(const Quaternion& quat);
35
42Quaternion ezyx_to_quat(const Vec3& ezyx);
43
50Mat3 quat_to_rot(const Quaternion& quat);
51
58Quaternion rot_to_quat(const Mat3& rot);
59
66Vec3 quat_to_rotvec(const Quaternion& quat);
67
74Quaternion rotvec_to_quat(const Vec3& rotvec);
75
83Mat3 rot_identity();
84
91Mat3 rot_rx(real_t rx);
92
99Mat3 rot_ry(real_t ry);
100
107Mat3 rot_rz(real_t rz);
108
116Vec3 rotate_mat3(const Mat3& rot, const Vec3& vec);
117
125Vec3 rotate_mat3_transpose(const Mat3& rot, const Vec3& vec);
126
131} // namespace fsb
132
133#endif
Mat3 rot_ry(real_t ry)
Rotation matrix about y-axis.
Definition fsb_rotation.cpp:27
Vec3 rotate_mat3_transpose(const Mat3 &rot, const Vec3 &vec)
Transposed matrix multiplication with rotation matrix.
Definition fsb_rotation.cpp:178
Mat3 quat_to_rot(const Quaternion &quat)
Convert unit quaternion to rotation matrix.
Definition fsb_rotation.cpp:86
Vec3 rotate_mat3(const Mat3 &rot, const Vec3 &vec)
Matrix multiplication with rotation matrix.
Definition fsb_rotation.cpp:169
Mat3 skew_symmetric(const Vec3 &vec)
Skew-symmetric matrix from vector.
Definition fsb_rotation.cpp:10
Quaternion ezyx_to_quat(const Vec3 &ezyx)
Convert intrinsic ZYX Euler-angles to unit quaternion.
Definition fsb_rotation.cpp:73
Quaternion rot_to_quat(const Mat3 &rot)
Convert rotation matrix to unit quaternion.
Definition fsb_rotation.cpp:103
Mat3 rot_identity()
Identity rotation matrix.
Definition fsb_rotation.cpp:15
Vec3 quat_to_ezyx(const Quaternion &quat)
Convert unit quaternion to intrinsic ZYX Euler-angles.
Definition fsb_rotation.cpp:41
Vec3 quat_to_rotvec(const Quaternion &quat)
Convert unit quaternion to rotation vector.
Definition fsb_rotation.cpp:154
Mat3 rot_rz(real_t rz)
Rotation matrix about z-axis.
Definition fsb_rotation.cpp:34
Mat3 rot_rx(real_t rx)
Rotation matrix about x-axis.
Definition fsb_rotation.cpp:20
Quaternion rotvec_to_quat(const Vec3 &rotvec)
Convert rotation vector to unit quaternion.
Definition fsb_rotation.cpp:163