CTRE Phoenix 6 C++ 26.50.0-alpha-1
Loading...
Searching...
No Matches
WheelForceCalculator.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
10#include <wpi/units/force.hpp>
11#include <wpi/units/moment_of_inertia.hpp>
12#include <wpi/units/torque.hpp>
13#include <vector>
14
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18
19/**
20 * Calculates wheel force feedforwards for a SwerveDrivetrain.
21 * Wheel force feedforwards can be used to improve accuracy of path
22 * following in regions of acceleration.
23 *
24 * Many path planning libraries (such as PathPlanner and Choreo) already
25 * provide per-module force feedforwards, which should be preferred over
26 * this class.
27 */
29public:
30 /** \brief Wheel force feedforwards to apply to a swerve drivetrain. */
31 struct Feedforwards {
32 /** \brief The X component of the forces in Newtons. */
33 std::vector<wpi::units::newton_t> x;
34 /** \brief The Y component of the forces in Newtons. */
35 std::vector<wpi::units::newton_t> y;
36
37 /**
38 * \brief Constructs a new set of wheel force feedforwards.
39 *
40 * \param numModules The number of swerve modules
41 */
42 Feedforwards(size_t numModules) :
43 x(numModules),
44 y(numModules)
45 {}
46 };
47
48private:
49 std::vector<Translation2d> moduleLocations;
50 wpi::units::kilogram_t mass;
51 wpi::units::kilogram_square_meter_t moi;
52
53public:
54 /**
55 * \brief Constructs a new wheel force feedforward calculator for the given
56 * drivetrain characteristics.
57 *
58 * \param moduleLocations The drivetrain swerve module locations
59 * \param mass The mass of the robot
60 * \param moi The moment of inertia of the robot
61 */
63 std::vector<Translation2d> moduleLocations,
64 wpi::units::kilogram_t mass,
65 wpi::units::kilogram_square_meter_t moi
66 ) :
67 moduleLocations{std::move(moduleLocations)},
68 mass{mass},
69 moi{moi}
70 {}
71
72 /**
73 * \brief Calculates wheel force feedforwards for the desired robot acceleration.
74 * This can be used with either robot-centric or field-centric accelerations;
75 * the returned force feedforwards will match in being robot-/field-centric.
76 *
77 * \param acceleration Acceleration of the robot
78 * \param centerOfRotation Center of rotation
79 * \returns Wheel force feedforwards to apply
80 */
82 ChassisAccelerations const &acceleration,
83 Translation2d const &centerOfRotation = {}
84 ) const {
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;
88
89 Feedforwards feedforwards{moduleLocations.size()};
90 for (size_t i = 0; i < moduleLocations.size(); ++i) {
91 Translation2d const r = moduleLocations[i] - centerOfRotation;
92
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();
96 }
97
98 return feedforwards;
99 }
100
101 /**
102 * \brief Calculates wheel force feedforwards for the desired change in velocity.
103 * This can be used with either robot-centric or field-centric velocities; the
104 * returned force feedforwards will match in being robot-/field-centric.
105 *
106 * \param dt The change in time between the path setpoints
107 * \param prev The previous ChassisVelocities setpoint of the path
108 * \param current The new ChassisVelocities setpoint of the path
109 * \param centerOfRotation Center of rotation
110 * \returns Wheel force feedforwards to apply
111 */
113 wpi::units::second_t dt,
114 ChassisVelocities const &prev,
115 ChassisVelocities const &current,
116 Translation2d const &centerOfRotation = {}
117 ) const {
118 ChassisAccelerations const accelerations{
119 (current.vx - prev.vx) / dt,
120 (current.vy - prev.vy) / dt,
121 (current.omega - prev.omega) / dt
122 };
123 return Calculate(accelerations, centerOfRotation);
124 }
125};
126
127}
128}
129}
Feedforwards Calculate(wpi::units::second_t dt, ChassisVelocities const &prev, ChassisVelocities const &current, Translation2d const &centerOfRotation={}) const
Calculates wheel force feedforwards for the desired change in velocity.
Definition WheelForceCalculator.hpp:112
Feedforwards Calculate(ChassisAccelerations const &acceleration, Translation2d const &centerOfRotation={}) 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