5#include "core/subsystems/custom_encoder.h"
6#include "core/subsystems/odometry/odometry_base.h"
7#include "core/utils/math_util.h"
52template <
int WHEELS>
class OdometryNWheel :
public OdometryBase {
63 const std::array<CustomEncoder, WHEELS> &encoders,
const std::array<tracking_wheel_cfg_t, WHEELS> wheel_configs,
64 vex::inertial *imu,
bool is_async
67 Eigen::Matrix<double, WHEELS, 3> transfer_matrix;
68 for (
int i = 0; i < WHEELS; i++) {
69 double x = wheel_configs[i].x;
70 double y = wheel_configs[i].y;
71 double theta_rad = wheel_configs[i].theta_rad;
72 double radius = wheel_configs[i].radius;
75 wheel_radii(i) = radius;
77 double x_factor = cos(theta_rad);
78 double y_factor = -sin(theta_rad);
79 double theta_factor = -(x * sin(theta_rad)) - (y * cos(theta_rad));
82 if (abs(y_factor) < 1e-9) {
85 if (abs(x_factor) < 1e-9) {
89 transfer_matrix.row(i) << x_factor, y_factor, theta_factor;
92 transfer_matrix_pseudoinverse = transfer_matrix.completeOrthogonalDecomposition().pseudoInverse();
94 old_wheel_angles.fill(0);
103 Pose2d update()
override {
104 Eigen::Vector<double, WHEELS> radian_deltas;
106 for (
int i = 0; i < WHEELS; i++) {
107 double angle_rad = encoders[i].position(rev) * M_PI * 2;
108 radian_deltas(i) = angle_rad - old_wheel_angles[i];
110 old_wheel_angles[i] = angle_rad;
113 Pose2d updated_pos = calculate_new_pos(radian_deltas,
current_pos);
116 if (imu !=
nullptr) {
119 angle = -imu->rotation(vex::rotationUnits::rev) * 2 * M_PI;
121 angle += angle_offset;
124 static Pose2d last_pos = updated_pos;
125 static double last_speed = 0;
126 static double last_ang_speed = 0;
129 double speed_local = 0;
130 double accel_local = 0;
131 double ang_speed_local = 0;
132 double ang_accel_local = 0;
133 bool update_vel_accel = tmr.time(sec) > 0.1;
136 if (update_vel_accel) {
141 accel_local = (speed_local - last_speed) / tmr.time(sec);
147 ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec);
150 last_pos = updated_pos;
151 last_speed = speed_local;
152 last_ang_speed = ang_speed_local;
156 if (update_vel_accel) {
157 this->
speed = speed_local;
158 this->
accel = accel_local;
163 if (imu !=
nullptr) {
173 void set_position(
const Pose2d &newpos)
override {
185 Pose2d get_position(
void) {
188 return with_wrapped_angle;
200 Pose2d calculate_new_pos(Eigen::Vector<double, WHEELS> radian_deltas, Pose2d old_pose) {
203 Eigen::Vector3d pose_delta = transfer_matrix_pseudoinverse * (radian_deltas.asDiagonal() * wheel_radii);
204 Eigen::Vector3d old_pose_vector{old_pose.
x(), old_pose.
y(), old_pose.
rotation().
degrees()};
207 if (imu !=
nullptr) {
208 pose_delta(2) = angle - old_angle;
210 Pose2d pose_delta2d(pose_delta);
211 Pose2d old_pose_Pose2d(old_pose_vector);
213 Pose2d new_pose = old_pose_Pose2d.exp(pose_delta);
216 if (imu !=
nullptr) {
229 Eigen::Matrix<double, 3, WHEELS> transfer_matrix_pseudoinverse;
231 std::array<CustomEncoder, WHEELS> encoders;
232 Eigen::Vector<double, WHEELS> wheel_radii;
234 Eigen::Vector<double, WHEELS> old_wheel_angles;
Definition odometry_base.h:31
double ang_accel_deg
Definition odometry_base.h:132
double ang_speed_deg
Definition odometry_base.h:131
Pose2d current_pos
Definition odometry_base.h:127
double speed
Definition odometry_base.h:129
OdometryBase(bool is_async)
Definition odometry_base.cpp:8
static double smallest_angle(double start_deg, double end_deg)
Definition odometry_base.cpp:78
vex::mutex mut
Definition odometry_base.h:122
double accel
Definition odometry_base.h:130
virtual Pose2d get_position(void)
Definition odometry_base.cpp:44
virtual void set_position(const Pose2d &newpos=zero_pos)
Definition odometry_base.cpp:58
Translation2d translation() const
Definition pose2d.cpp:62
double x() const
Definition pose2d.cpp:69
Rotation2d rotation() const
Definition pose2d.cpp:83
void setRotationDeg(double rotDeg)
Definition pose2d.cpp:87
double y() const
Definition pose2d.cpp:76
double wrapped_radians_360() const
Definition rotation2d.cpp:138
double degrees() const
Definition rotation2d.cpp:73
double distance(const Translation2d &other) const
Definition translation2d.cpp:79
Definition odometry_nwheel.h:45
double x
Definition odometry_nwheel.h:46
double radius
Definition odometry_nwheel.h:49
double theta_rad
Definition odometry_nwheel.h:48
double y
Definition odometry_nwheel.h:47