10#include <wpi/units/force.hpp>
11#include <wpi/units/moment_of_inertia.hpp>
12#include <wpi/units/torque.hpp>
33 std::vector<wpi::units::newton_t>
x;
35 std::vector<wpi::units::newton_t>
y;
49 std::vector<Translation2d> moduleLocations;
50 wpi::units::kilogram_t mass;
51 wpi::units::kilogram_square_meter_t moi;
63 std::vector<Translation2d> moduleLocations,
64 wpi::units::kilogram_t mass,
65 wpi::units::kilogram_square_meter_t moi
67 moduleLocations{std::move(moduleLocations)},
82 ChassisAccelerations
const &acceleration,
83 Translation2d
const ¢erOfRotation = {}
85 wpi::units::newton_t
const fx = acceleration.ax * mass;
86 wpi::units::newton_t
const fy = acceleration.ay * mass;
87 wpi::units::newton_meter_t
const tau = acceleration.alpha * moi / 1_rad;
89 Feedforwards feedforwards{moduleLocations.size()};
90 for (
size_t i = 0; i < moduleLocations.size(); ++i) {
91 Translation2d
const r = moduleLocations[i] - centerOfRotation;
93 Translation2d
const f_tau{tau / r.Norm() * 1_m/1_N, r.Angle() + Rotation2d{90_deg}};
94 feedforwards.x[i] = (fx + f_tau.X() * 1_N/1_m) / moduleLocations.size();
95 feedforwards.y[i] = (fy + f_tau.Y() * 1_N/1_m) / moduleLocations.size();
113 wpi::units::second_t dt,
114 ChassisVelocities
const &prev,
115 ChassisVelocities
const ¤t,
116 Translation2d
const ¢erOfRotation = {}
118 ChassisAccelerations
const accelerations{
119 (current.vx - prev.vx) / dt,
120 (current.vy - prev.vy) / dt,
121 (current.omega - prev.omega) / dt
123 return Calculate(accelerations, centerOfRotation);
Feedforwards Calculate(wpi::units::second_t dt, ChassisVelocities const &prev, ChassisVelocities const ¤t, Translation2d const ¢erOfRotation={}) const
Calculates wheel force feedforwards for the desired change in velocity.
Definition WheelForceCalculator.hpp:112
Feedforwards Calculate(ChassisAccelerations const &acceleration, Translation2d const ¢erOfRotation={}) const
Calculates wheel force feedforwards for the desired robot acceleration.
Definition WheelForceCalculator.hpp:81
WheelForceCalculator(std::vector< Translation2d > moduleLocations, wpi::units::kilogram_t mass, wpi::units::kilogram_square_meter_t moi)
Constructs a new wheel force feedforward calculator for the given drivetrain characteristics.
Definition WheelForceCalculator.hpp:62
Definition SwerveModule.hpp:28
Definition ExternalFeedbackConfigs.hpp:16
Definition motor_constants.h:14
Wheel force feedforwards to apply to a swerve drivetrain.
Definition WheelForceCalculator.hpp:31
std::vector< wpi::units::newton_t > y
The Y component of the forces in Newtons.
Definition WheelForceCalculator.hpp:35
std::vector< wpi::units::newton_t > x
The X component of the forces in Newtons.
Definition WheelForceCalculator.hpp:33
Feedforwards(size_t numModules)
Constructs a new set of wheel force feedforwards.
Definition WheelForceCalculator.hpp:42