RIT VEXU Core API
Loading...
Searching...
No Matches
odometry_nwheel.h
1#pragma once
2
3#include <Eigen/Dense>
4
5#include "core/subsystems/custom_encoder.h"
6#include "core/subsystems/odometry/odometry_base.h"
7#include "core/utils/math_util.h"
8
40
45typedef struct {
46 double x;
47 double y;
48 double theta_rad;
49 double radius;
51
52template <int WHEELS> class OdometryNWheel : public OdometryBase {
53public:
62 OdometryNWheel(
63 const std::array<CustomEncoder, WHEELS> &encoders, const std::array<tracking_wheel_cfg_t, WHEELS> wheel_configs,
64 vex::inertial *imu, bool is_async
65 )
66 : OdometryBase(is_async), imu(imu), encoders(encoders) {
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;
73 // Eigen::Vector of the radii of the tracking wheels
74 // defined at the bottom of private:
75 wheel_radii(i) = radius;
76
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));
80
81 // prevent numerical error due to float precision
82 if (abs(y_factor) < 1e-9) {
83 y_factor = 0;
84 }
85 if (abs(x_factor) < 1e-9) {
86 x_factor = 0;
87 }
88
89 transfer_matrix.row(i) << x_factor, y_factor, theta_factor;
90 }
91
92 transfer_matrix_pseudoinverse = transfer_matrix.completeOrthogonalDecomposition().pseudoInverse();
93 angle_offset = 0;
94 old_wheel_angles.fill(0);
95 }
96
103 Pose2d update() override {
104 Eigen::Vector<double, WHEELS> radian_deltas;
105
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];
109
110 old_wheel_angles[i] = angle_rad;
111 }
112
113 Pose2d updated_pos = calculate_new_pos(radian_deltas, current_pos);
114
115 // if we do not pass in an IMU we use the wheels for rotation
116 if (imu != nullptr) {
117 angle = 0;
118 // Translate "0 forward and clockwise positive" to "CCW positive and radians"
119 angle = -imu->rotation(vex::rotationUnits::rev) * 2 * M_PI;
120 // Offset the angle, if we've done a set_position
121 angle += angle_offset;
122 }
123
124 static Pose2d last_pos = updated_pos;
125 static double last_speed = 0;
126 static double last_ang_speed = 0;
127 static timer tmr;
128
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;
134
135 // This loop runs too fast. Only check at LEAST every 1/10th sec
136 if (update_vel_accel) {
137 // Calculate robot velocity
138 speed_local = updated_pos.translation().distance(last_pos.translation()) / tmr.time(sec);
139
140 // Calculate robot acceleration
141 accel_local = (speed_local - last_speed) / tmr.time(sec);
142
143 // Calculate robot angular velocity (deg/sec)
144 ang_speed_local = smallest_angle(updated_pos.rotation().degrees(), last_pos.rotation().degrees()) / tmr.time(sec);
145
146 // Calculate robot angular acceleration (deg/sec^2)
147 ang_accel_local = (ang_speed_local - last_ang_speed) / tmr.time(sec);
148
149 tmr.reset();
150 last_pos = updated_pos;
151 last_speed = speed_local;
152 last_ang_speed = ang_speed_local;
153 }
154
155 this->current_pos = updated_pos;
156 if (update_vel_accel) {
157 this->speed = speed_local;
158 this->accel = accel_local;
159 this->ang_speed_deg = ang_speed_local;
160 this->ang_accel_deg = ang_accel_local;
161 }
162
163 if (imu != nullptr) {
164 old_angle = angle;
165 }
166
167 return current_pos;
168 }
169
173 void set_position(const Pose2d &newpos) override {
174 mut.lock();
175 angle_offset = newpos.rotation().degrees() - (current_pos.rotation().degrees() - angle_offset);
176 mut.unlock();
177
179 }
180
185 Pose2d get_position(void) {
186 Pose2d without_wrapped_angle = OdometryBase::get_position();
187 Pose2d with_wrapped_angle(without_wrapped_angle.translation(), without_wrapped_angle.rotation().wrapped_radians_360());
188 return with_wrapped_angle;
189 }
190
191private:
200 Pose2d calculate_new_pos(Eigen::Vector<double, WHEELS> radian_deltas, Pose2d old_pose) {
201 // Mr T = E -> Mr^{+} E = T
202 // We take the diagonal of radian_deltas to do a coefficient wise multiplication rather than a dot product
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()};
205 // we achieve better performance by using the imu for rotation directly when possible
206 // If an imu is not passed in when constructing, simply use the wheels for rotation
207 if (imu != nullptr) {
208 pose_delta(2) = angle - old_angle;
209 }
210 Pose2d pose_delta2d(pose_delta);
211 Pose2d old_pose_Pose2d(old_pose_vector);
212
213 Pose2d new_pose = old_pose_Pose2d.exp(pose_delta);
214
215 // simply replaces the calculated angle with the imu angle directly
216 if (imu != nullptr) {
217 new_pose.setRotationDeg(angle);
218 }
219 return new_pose;
220 }
221
222 // values used for imu integration
223 double angle;
224 double old_angle;
225 double angle_offset;
226
227 vex::inertial *imu;
228
229 Eigen::Matrix<double, 3, WHEELS> transfer_matrix_pseudoinverse;
230
231 std::array<CustomEncoder, WHEELS> encoders;
232 Eigen::Vector<double, WHEELS> wheel_radii;
233 // from the last timestep, used for finding deltas
234 Eigen::Vector<double, WHEELS> old_wheel_angles;
235};
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