Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[wpimath] Add feedforward constant constructor to ElevatorSim #5823

Merged
merged 82 commits into from
Nov 2, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
82 commits
Select commit Hold shift + click to select a range
3a6103f
added nextV calc methods to ArmFF & Elevator FF
narmstro2020 Oct 2, 2023
57867c7
revert ArmFeedForward back
narmstro2020 Oct 2, 2023
181ec2f
ArmFF newline at EOF, ElevatorFF note about 0
narmstro2020 Oct 2, 2023
3583ac3
Added Derivation to Elevator FF nextV method
narmstro2020 Oct 2, 2023
88b60f4
Derivation repositioned
narmstro2020 Oct 2, 2023
70dad83
Update wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFe…
narmstro2020 Oct 2, 2023
533759e
fixing comments
narmstro2020 Oct 2, 2023
4bee24d
more comment fixing
narmstro2020 Oct 2, 2023
09dabe2
commenting fixing again
narmstro2020 Oct 2, 2023
b4ad348
p tag issue
narmstro2020 Oct 2, 2023
9834f99
p tag commenting fix again
narmstro2020 Oct 2, 2023
7fedd14
commenting fixes
narmstro2020 Oct 2, 2023
a8d0408
Clean up comments
calcmogul Oct 2, 2023
fadd134
comment fixes
narmstro2020 Oct 2, 2023
ef1a14d
Add C++ version
calcmogul Oct 3, 2023
cd9c3d0
Tests for new ElevatorFeedForward calculate method
narmstro2020 Oct 8, 2023
b86ca36
Elevator Test import cleanup
narmstro2020 Oct 8, 2023
bc2eab5
ElevatorFeedforwardTest c++ V nextV calculate
narmstro2020 Oct 9, 2023
227794f
Cleanup
narmstro2020 Oct 9, 2023
7383447
moved asserts
narmstro2020 Oct 9, 2023
8f955cb
fixed dt
narmstro2020 Oct 9, 2023
90fcc60
added newlines
narmstro2020 Oct 9, 2023
2d812e3
added another newline
narmstro2020 Oct 9, 2023
4dc0c3e
fixed dt
narmstro2020 Oct 9, 2023
532194f
units on 0.020 s
narmstro2020 Oct 9, 2023
41525db
[build] Remove unnecessary CMake config installs (#5714)
Gold856 Oct 2, 2023
9e05ab8
[ci] Fix -dirty version (#5716)
PeterJohnson Oct 2, 2023
eabf2f1
[wpiutil] SendableBuilder: Add PublishConst methods (#5158)
Starlight220 Oct 2, 2023
95afbaa
[wpigui] Fix loading a maximized window on second monitor (#5721)
ohowe1 Oct 3, 2023
871b73d
[wpiutil] Get more precise system time on Windows (#5722)
PeterJohnson Oct 4, 2023
c5b5495
[wpinet] Revert removal of uv_clock_gettime() (#5723)
calcmogul Oct 4, 2023
58a6193
[build] Update to gradle 8.4, enable win arm builds (#5727)
ThadHouse Oct 5, 2023
6cc4924
[wpilib] SendableChooser: implement Sendable instead of NTSendable (#…
Gold856 Oct 5, 2023
e282743
[wpilib] Make BooleanEvent more consistent (#5436)
Gold856 Oct 5, 2023
4a79742
[wpiutil] Set WPI_{UN}IGNORE_DEPRECATED to empty when all else fails …
virtuald Oct 5, 2023
36a9931
[ntcore] Networking improvements (#5659)
PeterJohnson Oct 5, 2023
b581f85
[commands] Clean up C++ includes after Requirements was added (#5719)
rzblue Oct 5, 2023
4095c46
[build] Update enterprise plugin (#5730)
ThadHouse Oct 5, 2023
287fc74
[ntcore] Fix notification of SetDefaultEntryValue (#5733)
PeterJohnson Oct 8, 2023
761867b
[ntcore] Fix moving outgoing queue to new period (#5735)
PeterJohnson Oct 8, 2023
3e72813
[ntcore] Add RTT-only subprotocol (#5731)
PeterJohnson Oct 8, 2023
18ef57f
Fix test organization
calcmogul Oct 9, 2023
7cbf67c
Merge branch 'main' into narmstro2020/main
calcmogul Oct 9, 2023
f6879df
Fix Java formatting
calcmogul Oct 9, 2023
11f6502
Merge branch 'wpilibsuite:main' into main
narmstro2020 Oct 16, 2023
91e1afd
Merge branch 'wpilibsuite:main' into main
narmstro2020 Oct 18, 2023
d66c4ba
Merge branch 'wpilibsuite:main' into main
narmstro2020 Oct 21, 2023
e114a28
Merge branch 'wpilibsuite:main' into main
narmstro2020 Oct 25, 2023
61a42a3
Imported ElevatorySimSysId java
narmstro2020 Oct 25, 2023
ec83c32
minor fixes to formatting
narmstro2020 Oct 25, 2023
c3fd235
revised Constructor for ElevatorSim
narmstro2020 Oct 25, 2023
3a47616
Fix to Constructor
narmstro2020 Oct 26, 2023
1839f75
fixed missing import
narmstro2020 Oct 26, 2023
de21da1
fixed JavaDocs
narmstro2020 Oct 26, 2023
354979b
removed redundant import
narmstro2020 Oct 26, 2023
d64f5b7
removed extra space
narmstro2020 Oct 26, 2023
59294cf
removed sysid folder
narmstro2020 Oct 26, 2023
8f54a9e
Formatting fixes
github-actions[bot] Oct 28, 2023
c08b4ae
removed drumRadius and mass from gains constructor
narmstro2020 Oct 31, 2023
f093754
eliminate private fields or gearing and drumRadius
narmstro2020 Oct 31, 2023
411a82c
fixed typo
narmstro2020 Oct 31, 2023
112a121
fixed doc issue
narmstro2020 Oct 31, 2023
d12f404
line width linting issue
narmstro2020 Oct 31, 2023
9c70013
line length fixes
narmstro2020 Oct 31, 2023
f7f7faf
spotlessApply
narmstro2020 Oct 31, 2023
b0c6a0a
C++ code commit
narmstro2020 Oct 31, 2023
b3eb155
c++ documentation fix
narmstro2020 Oct 31, 2023
89312ad
additional cpp doc fix
narmstro2020 Oct 31, 2023
d282d19
template adjustment cpp
narmstro2020 Oct 31, 2023
1d5da55
added units include
narmstro2020 Oct 31, 2023
2e8e9fc
fix to template
narmstro2020 Oct 31, 2023
afdfd6c
unit issue
narmstro2020 Oct 31, 2023
1f77f7e
another unit fix
narmstro2020 Oct 31, 2023
f6a0327
units fix again
narmstro2020 Oct 31, 2023
51e5bac
Formatting fixes
github-actions[bot] Oct 31, 2023
59680e3
possible unit fix
narmstro2020 Oct 31, 2023
3f7fc17
Merge branch 'ElevatorSimSysId' of https://github.com/narmstro2020/al…
narmstro2020 Oct 31, 2023
1119259
unit type declared properly
narmstro2020 Oct 31, 2023
0dd6352
Formatting fixes
github-actions[bot] Oct 31, 2023
5a7f05a
comment removed
narmstro2020 Oct 31, 2023
2a4f4d8
fixed documentation
narmstro2020 Oct 31, 2023
2e472b0
fixed docs again
narmstro2020 Oct 31, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 21 additions & 9 deletions wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,17 +13,14 @@ using namespace frc;
using namespace frc::sim;

ElevatorSim::ElevatorSim(const LinearSystem<2, 1, 1>& plant,
const DCMotor& gearbox, double gearing,
calcmogul marked this conversation as resolved.
Show resolved Hide resolved
units::meter_t drumRadius, units::meter_t minHeight,
const DCMotor& gearbox, units::meter_t minHeight,
units::meter_t maxHeight, bool simulateGravity,
units::meter_t startingHeight,
const std::array<double, 1>& measurementStdDevs)
: LinearSystemSim(plant, measurementStdDevs),
m_gearbox(gearbox),
m_drumRadius(drumRadius),
m_minHeight(minHeight),
m_maxHeight(maxHeight),
m_gearing(gearing),
m_simulateGravity(simulateGravity) {
SetState(startingHeight, 0_mps);
}
Expand All @@ -36,8 +33,21 @@ ElevatorSim::ElevatorSim(const DCMotor& gearbox, double gearing,
const std::array<double, 1>& measurementStdDevs)
: ElevatorSim(LinearSystemId::ElevatorSystem(gearbox, carriageMass,
drumRadius, gearing),
gearbox, gearing, drumRadius, minHeight, maxHeight,
simulateGravity, startingHeight, measurementStdDevs) {}
gearbox, minHeight, maxHeight, simulateGravity,
startingHeight, measurementStdDevs) {}

template <typename Distance>
requires std::same_as<units::meter, Distance> ||
std::same_as<units::radian, Distance>
ElevatorSim::ElevatorSim(decltype(1_V / Velocity_t<Distance>(1)) kV,
decltype(1_V / Acceleration_t<Distance>(1)) kA,
const DCMotor& gearbox, units::meter_t minHeight,
units::meter_t maxHeight, bool simulateGravity,
units::meter_t startingHeight,
const std::array<double, 1>& measurementStdDevs)
: ElevatorSim(LinearSystemId::IdentifyPositionSystem(kV, kA), gearbox,
minHeight, maxHeight, simulateGravity, startingHeight,
measurementStdDevs) {}

void ElevatorSim::SetState(units::meter_t position,
units::meters_per_second_t velocity) {
Expand Down Expand Up @@ -74,10 +84,12 @@ units::ampere_t ElevatorSim::GetCurrentDraw() const {
// Reductions are greater than 1, so a reduction of 10:1 would mean the motor
// is spinning 10x faster than the output.

// v = r w, so w = v / r
double kA = 1.0 / m_plant.B(1, 0);
using Kv_t = units::unit_t<units::compound_unit<
units::volt, units::inverse<units::meters_per_second>>>;
Kv_t Kv = Kv_t{kA * m_plant.A(1, 1)};
units::meters_per_second_t velocity{m_x(1)};
units::radians_per_second_t motorVelocity =
velocity / m_drumRadius * m_gearing * 1_rad;
units::radians_per_second_t motorVelocity = velocity * Kv * m_gearbox.Kv;

// Perform calculation and return.
return m_gearbox.Current(motorVelocity, units::volt_t{m_u(0)}) *
Expand Down
38 changes: 31 additions & 7 deletions wpilibc/src/main/native/include/frc/simulation/ElevatorSim.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,15 @@ namespace frc::sim {
*/
class ElevatorSim : public LinearSystemSim<2, 1, 1> {
public:
template <typename Distance>
using Velocity_t = units::unit_t<
units::compound_unit<Distance, units::inverse<units::seconds>>>;

template <typename Distance>
using Acceleration_t = units::unit_t<units::compound_unit<
units::compound_unit<Distance, units::inverse<units::seconds>>,
units::inverse<units::seconds>>>;

/**
* Constructs a simulated elevator mechanism.
*
Expand All @@ -27,18 +36,13 @@ class ElevatorSim : public LinearSystemSim<2, 1, 1> {
* LinearSystemId::ElevatorSystem().
* @param gearbox The type of and number of motors in your
* elevator gearbox.
* @param gearing The gearing of the elevator (numbers greater
* than 1 represent reductions).
* @param drumRadius The radius of the drum that your cable is
* wrapped around.
* @param minHeight The minimum allowed height of the elevator.
* @param maxHeight The maximum allowed height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
* @param startingHeight The starting height of the elevator.
* @param measurementStdDevs The standard deviation of the measurements.
*/
ElevatorSim(const LinearSystem<2, 1, 1>& plant, const DCMotor& gearbox,
double gearing, units::meter_t drumRadius,
units::meter_t minHeight, units::meter_t maxHeight,
bool simulateGravity, units::meter_t startingHeight,
const std::array<double, 1>& measurementStdDevs = {0.0});
Expand All @@ -65,6 +69,28 @@ class ElevatorSim : public LinearSystemSim<2, 1, 1> {
bool simulateGravity, units::meter_t startingHeight,
const std::array<double, 1>& measurementStdDevs = {0.0});

/**
* Constructs a simulated elevator mechanism.
*
* @param kV The velocity gain.
* @param kA The acceleration gain.
* @param gearbox The type of and number of motors in your
* elevator gearbox.
* @param minHeight The minimum allowed height of the elevator.
* @param maxHeight The maximum allowed height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
* @param startingHeight The starting height of the elevator.
* @param measurementStdDevs The standard deviation of the measurements.
*/
template <typename Distance>
requires std::same_as<units::meter, Distance> ||
std::same_as<units::radian, Distance>
ElevatorSim(decltype(1_V / Velocity_t<Distance>(1)) kV,
decltype(1_V / Acceleration_t<Distance>(1)) kA,
const DCMotor& gearbox, units::meter_t minHeight,
units::meter_t maxHeight, bool simulateGravity,
units::meter_t startingHeight,
const std::array<double, 1>& measurementStdDevs = {0.0});
using LinearSystemSim::SetState;

/**
Expand Down Expand Up @@ -146,10 +172,8 @@ class ElevatorSim : public LinearSystemSim<2, 1, 1> {

private:
DCMotor m_gearbox;
units::meter_t m_drumRadius;
units::meter_t m_minHeight;
units::meter_t m_maxHeight;
double m_gearing;
bool m_simulateGravity;
};
} // namespace frc::sim
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,6 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N1> {
// Gearbox for the elevator.
private final DCMotor m_gearbox;

// Gearing between the motors and the output.
private final double m_gearing;

// The radius of the drum that the elevator spool is wrapped around.
private final double m_drumRadius;

// The min allowable height for the elevator.
private final double m_minHeight;

Expand All @@ -41,8 +35,6 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N1> {
* {@link edu.wpi.first.math.system.plant.LinearSystemId#createElevatorSystem(DCMotor, double,
* double, double)}.
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param gearing The gearing of the elevator (numbers greater than 1 represent reductions).
* @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
* @param minHeightMeters The min allowable height of the elevator.
* @param maxHeightMeters The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
Expand All @@ -52,17 +44,13 @@ public class ElevatorSim extends LinearSystemSim<N2, N1, N1> {
public ElevatorSim(
LinearSystem<N2, N1, N1> plant,
DCMotor gearbox,
double gearing,
double drumRadiusMeters,
double minHeightMeters,
double maxHeightMeters,
boolean simulateGravity,
double startingHeightMeters,
Matrix<N1, N1> measurementStdDevs) {
super(plant, measurementStdDevs);
m_gearbox = gearbox;
m_gearing = gearing;
m_drumRadius = drumRadiusMeters;
m_minHeight = minHeightMeters;
m_maxHeight = maxHeightMeters;
m_simulateGravity = simulateGravity;
Expand All @@ -77,8 +65,6 @@ public ElevatorSim(
* {@link edu.wpi.first.math.system.plant.LinearSystemId#createElevatorSystem(DCMotor, double,
* double, double)}.
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param gearing The gearing of the elevator (numbers greater than 1 represent reductions).
* @param drumRadiusMeters The radius of the drum that the elevator spool is wrapped around.
* @param minHeightMeters The min allowable height of the elevator.
* @param maxHeightMeters The max allowable height of the elevator.
* @param startingHeightMeters The starting height of the elevator.
Expand All @@ -87,24 +73,81 @@ public ElevatorSim(
public ElevatorSim(
LinearSystem<N2, N1, N1> plant,
DCMotor gearbox,
double gearing,
double drumRadiusMeters,
double minHeightMeters,
double maxHeightMeters,
boolean simulateGravity,
double startingHeightMeters) {
this(
plant,
gearbox,
gearing,
drumRadiusMeters,
minHeightMeters,
maxHeightMeters,
simulateGravity,
startingHeightMeters,
null);
}

/**
* Creates a simulated elevator mechanism.
*
* @param kV The velocity gain.
* @param kA The acceleration gain.
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param minHeightMeters The min allowable height of the elevator.
* @param maxHeightMeters The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
* @param startingHeightMeters The starting height of the elevator.
*/
public ElevatorSim(
double kV,
double kA,
DCMotor gearbox,
Copy link
Member

@calcmogul calcmogul Oct 26, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You forgot Kv and Ka. That replaces the gearbox, gearing, and drum radius.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do I need to remove KG?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm a little lost. Should kV, kA, and kG be capable of generating the gearbox, gearing, and drumRadius fields that are required?

double minHeightMeters,
double maxHeightMeters,
boolean simulateGravity,
double startingHeightMeters) {
this(
kV,
kA,
gearbox,
minHeightMeters,
maxHeightMeters,
simulateGravity,
startingHeightMeters,
null);
}

/**
* Creates a simulated elevator mechanism.
*
* @param kV The velocity gain.
* @param kA The acceleration gain.
* @param gearbox The type of and number of motors in the elevator gearbox.
* @param minHeightMeters The min allowable height of the elevator.
* @param maxHeightMeters The max allowable height of the elevator.
* @param simulateGravity Whether gravity should be simulated or not.
* @param startingHeightMeters The starting height of the elevator.
* @param measurementStdDevs The standard deviations of the measurements.
*/
public ElevatorSim(
double kV,
double kA,
DCMotor gearbox,
double minHeightMeters,
double maxHeightMeters,
boolean simulateGravity,
double startingHeightMeters,
Matrix<N1, N1> measurementStdDevs) {
this(
LinearSystemId.identifyPositionSystem(kV, kA),
gearbox,
minHeightMeters,
maxHeightMeters,
simulateGravity,
startingHeightMeters,
measurementStdDevs);
}

/**
* Creates a simulated elevator mechanism.
*
Expand All @@ -131,8 +174,6 @@ public ElevatorSim(
this(
LinearSystemId.createElevatorSystem(gearbox, carriageMassKg, drumRadiusMeters, gearing),
gearbox,
gearing,
drumRadiusMeters,
minHeightMeters,
maxHeightMeters,
simulateGravity,
Expand Down Expand Up @@ -253,7 +294,10 @@ public double getCurrentDrawAmps() {
// Reductions are greater than 1, so a reduction of 10:1 would mean the motor is
// spinning 10x faster than the output
// v = r w, so w = v/r
double motorVelocityRadPerSec = getVelocityMetersPerSecond() / m_drumRadius * m_gearing;
double kA = 1 / m_plant.getB().get(1, 0);
double kV = -m_plant.getA().get(1, 1) * kA;
double motorVelocityRadPerSec =
getVelocityMetersPerSecond() * kV * m_gearbox.KvRadPerSecPerVolt;
var appliedVoltage = m_u.get(0, 0);
return m_gearbox.getCurrent(motorVelocityRadPerSec, appliedVoltage)
* Math.signum(appliedVoltage);
Expand Down