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 vector slewrate limiter #7806

Open
wants to merge 49 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 35 commits
Commits
Show all changes
49 commits
Select commit Hold shift + click to select a range
b1a274c
Added function to Translation2d and Translation3d classes
OhmV-IR Feb 17, 2025
2cbe901
is compiling, tests still not working though
OhmV-IR Feb 18, 2025
f9cd60a
Fixed tests
OhmV-IR Feb 19, 2025
9e67108
Math fixes
OhmV-IR Feb 20, 2025
8bfae4e
Fix tests
OhmV-IR Feb 20, 2025
2faae65
Move tests to MathUtilTest
OhmV-IR Feb 20, 2025
bf3c2e6
Move SlewRateLimit functions to MathUtil.h
OhmV-IR Feb 20, 2025
f3d44ef
Fix include errors
OhmV-IR Feb 20, 2025
31fe090
Fix to not use private members
OhmV-IR Feb 20, 2025
12ba12d
Add missing namespace in front of translation classes
OhmV-IR Feb 20, 2025
024a03e
fix reference to SlewRateLimit as a part of translation2/3d
OhmV-IR Feb 20, 2025
c047ca5
Add java code
OhmV-IR Feb 20, 2025
cf9dca2
move imports under package declaration
OhmV-IR Feb 20, 2025
d9f2535
Fix to use template shown in issue description
OhmV-IR Feb 20, 2025
b84ffdf
Make cpp code match java code in functionality
OhmV-IR Feb 20, 2025
fe10053
Fix reportError call in cpp code
OhmV-IR Feb 20, 2025
0056a17
typo fix
OhmV-IR Feb 20, 2025
6cdc391
Fix style violations
OhmV-IR Feb 20, 2025
f258a55
Switch to using Math.min function instead of if statement
OhmV-IR Feb 20, 2025
ed94877
whoops forgot a few Math.mins
OhmV-IR Feb 20, 2025
87fd5e6
Update wpimath/src/main/native/include/frc/MathUtil.h
OhmV-IR Feb 20, 2025
d3776aa
Update wpimath/src/main/native/include/frc/MathUtil.h
OhmV-IR Feb 20, 2025
5852c95
fix build error
OhmV-IR Feb 21, 2025
f8481ec
Update wpimath/src/main/native/include/frc/MathUtil.h
OhmV-IR Feb 21, 2025
a040902
Move #include to MathUtil.h
OhmV-IR Feb 21, 2025
402c546
Remove changes to Translation2d.h and Translation3d.h
OhmV-IR Feb 21, 2025
835addb
Fix logic
OhmV-IR Feb 21, 2025
ab37b4c
Revert changes to Translation2dTest.cpp and Translation3dTest.cpp
OhmV-IR Feb 21, 2025
483e4eb
Update wpimath/src/main/native/include/frc/MathUtil.h
OhmV-IR Feb 21, 2025
c8680b1
Update wpimath/src/main/native/include/frc/MathUtil.h
OhmV-IR Feb 21, 2025
2ec1d5a
Update wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
OhmV-IR Feb 21, 2025
4c64925
Update wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
OhmV-IR Feb 21, 2025
16c840a
Update wpimath/src/test/native/cpp/MathUtilTest.cpp
OhmV-IR Feb 21, 2025
4f82689
Update wpimath/src/test/native/cpp/MathUtilTest.cpp
OhmV-IR Feb 21, 2025
2693aa0
Put Translation2d test before Translation3d test
OhmV-IR Feb 21, 2025
9bd3959
Fix syntax error
OhmV-IR Feb 21, 2025
c40ee19
Add missing include statement
OhmV-IR Feb 21, 2025
2d70846
Fix the use of inv_sqrt2 which actually isn't defined in std::numbers
OhmV-IR Feb 21, 2025
06a80cd
add return after MathSharedStore::ReportError
OhmV-IR Feb 21, 2025
ca60535
Another syntax fix
OhmV-IR Feb 21, 2025
aa6ec61
Fix style violations
OhmV-IR Feb 21, 2025
fe89009
Run spotlessjava apply
OhmV-IR Feb 21, 2025
8bcba94
Separate tests into semantic sections
OhmV-IR Feb 22, 2025
ec967d8
Add @return doc comments for linter
OhmV-IR Feb 22, 2025
e5e7f66
Remove newlines at end of files
OhmV-IR Feb 22, 2025
5c8e271
Apply spotless
OhmV-IR Feb 22, 2025
c3bae7a
Update wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
OhmV-IR Feb 22, 2025
df2fb4c
Update wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
OhmV-IR Feb 22, 2025
b945583
Apply wpiformat changes
OhmV-IR Feb 22, 2025
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
57 changes: 57 additions & 0 deletions wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@

package edu.wpi.first.math;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;

/** Math utility functions. */
public final class MathUtil {
private MathUtil() {
Expand Down Expand Up @@ -209,4 +212,58 @@ public static boolean isNear(
double error = MathUtil.inputModulus(expected - actual, -errorBound, errorBound);
return Math.abs(error) < tolerance;
}

/**
* Limits translation velocity.
*
* @param current Translation at current timestep.
* @param next Translation at next timestep.
* @param dt Timestep duration.
* @param maxVelocity Maximum translation velocity.
*/
public static Translation2d slewRateLimit(
Translation2d current, Translation2d next, double dt, double maxVelocity) {
if (maxVelocity < 0) {
Exception e = new IllegalArgumentException();
MathSharedStore.reportError(
"maxVelocity must be a non-negative number, got " + maxVelocity, e.getStackTrace());
}
Translation2d diff = next.minus(current);
double dist = diff.getNorm();
if (dist < 1e-9) {
return next;
}
if (dist > maxVelocity * dt) {
// Move maximum allowed amount in direction of the difference
return current.plus(diff.times(maxVelocity * dt).div(dist));
}
return next;
}

/**
* Limits translation velocity.
*
* @param current Translation at current timestep.
* @param next Translation at next timestep.
* @param dt Timestep duration.
* @param maxVelocity Maximum translation velocity.
*/
public static Translation3d slewRateLimit(
Translation3d current, Translation3d next, double dt, double maxVelocity) {
if (maxVelocity < 0) {
Exception e = new IllegalArgumentException();
MathSharedStore.reportError(
"maxVelocity must be a non-negative number, got " + maxVelocity, e.getStackTrace());
}
Translation3d diff = next.minus(current);
double dist = diff.getNorm();
if (dist < 1e-9) {
return next;
}
if (dist > maxVelocity * dt) {
// Move maximum allowed amount in direction of the difference
return current.plus(diff.times(maxVelocity * dt).div(dist));
}
return next;
}
}
62 changes: 62 additions & 0 deletions wpimath/src/main/native/include/frc/MathUtil.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,12 @@
#include "units/angle.h"
#include "units/base.h"
#include "units/math.h"
#include "frc/geometry/Translation3d.h"
#include "frc/geometry/Translation2d.h"
#include "units/time.h"
#include "units/velocity.h"
#include "units/length.h"
#include "wpimath/MathShared.h"

namespace frc {

Expand Down Expand Up @@ -207,4 +213,60 @@ constexpr std::signed_integral auto FloorMod(std::signed_integral auto x,
std::signed_integral auto y) {
return x - FloorDiv(x, y) * y;
}

/**
* Limits translation velocity.
*
* @param current Translation at current timestep.
* @param next Translation at next timestep.
* @param dt Timestep duration.
* @param maxVelocity Maximum translation velocity.
*/
constexpr Translation2d SlewRateLimit(const Translation2d& current,
const Translation2d& next,
units::second_t dt,
units::meters_per_second_t maxVelocity) {
if (maxVelocity < 0_mps) {
wpi::math::MathSharedStore::ReportError(
"maxVelocity must be a non-negative number, got {}!", maxVelocity.value());
}
Translation2d diff = next - current;
units::meter_t dist = diff.Norm();
if (dist < 1e-9_m) {
return next;
}
if (dist > maxVelocity * dt) {
// Move maximum allowed amount in direction of the difference
return current + diff * (maxVelocity * dt / dist).value();
}
return next;
}

/**
* Limits translation velocity.
*
* @param current Translation at current timestep.
* @param next Translation at next timestep.
* @param dt Timestep duration.
* @param maxVelocity Maximum translation velocity.
*/
constexpr Translation3d SlewRateLimit(
const Translation3d& current, const Translation3d& next, units::second_t dt,
units::meters_per_second_t maxVelocity) {
if (maxVelocity < 0_mps) {
wpi::math::MathSharedStore::ReportError(
"maxVelocity must be a non-negative number, got {}!", maxVelocity.value());
}
Translation3d diff = next - current;
units::meter_t dist = diff.Norm();
if (dist < 1e-9_m) {
return next;
}
if (dist > maxVelocity * dt) {
// Move maximum allowed amount in direction of the difference
return current + diff * (maxVelocity * dt / dist).value();
}
return next;
}

} // namespace frc
30 changes: 30 additions & 0 deletions wpimath/src/test/java/edu/wpi/first/math/MathUtilTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
import static org.junit.jupiter.api.Assertions.assertFalse;
import static org.junit.jupiter.api.Assertions.assertTrue;

import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.wpilibj.UtilityClassTest;
import org.junit.jupiter.api.Test;

Expand Down Expand Up @@ -167,4 +169,32 @@ void testIsNear() {
assertFalse(MathUtil.isNear(400, -315, 5, 0, 360));
assertFalse(MathUtil.isNear(400, 395, 5, 0, 360));
}

@Test
void testSlewRateTranslation2d() {
Translation2d translation1 = new Translation2d(0, 0);
Translation2d translation2 = new Translation2d(2, 2);
Translation2d translation3 = new Translation2d(1, 1);
Translation2d translation4 = new Translation2d(3, 3);
Translation2d result1 = MathUtil.slewRateLimit(translation1, translation2, 1, 50);
Translation2d result2 = MathUtil.slewRateLimit(translation3, translation4, 0.25, 2);
Translation2d expected1 = new Translation2d(2, 2);
Translation2d expected2 = new Translation2d(1.0 + 1.0 / Math.sqrt(8.0), 1.0 + 1.0 / Math.sqrt(8.0));
assertEquals(expected1, result1);
assertEquals(expected2, result2);
}

@Test
void testSlewRateTranslation3d() {
Translation3d translation1 = new Translation3d(0, 0, 0);
Translation3d translation2 = new Translation3d(2, 2, 2);
Translation3d translation3 = new Translation3d(1, 1, 1);
Translation3d translation4 = new Translation3d(3, 3, 3);
Translation3d result1 = MathUtil.slewRateLimit(translation1, translation2, 1, 50);
Translation3d result2 = MathUtil.slewRateLimit(translation3, translation4, 0.25, 2);
Translation3d expected1 = new Translation3d(2, 2, 2);
Translation3d expected2 = new Translation3d(1.0 + 1.0 / Math.sqrt(12.0), 1.0 + 1.0 / Math.sqrt(12.0), 1.0 + 1.0 / Math.sqrt(12.0));
assertEquals(expected1, result1);
assertEquals(expected2, result2);
}
}
31 changes: 31 additions & 0 deletions wpimath/src/test/native/cpp/MathUtilTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,11 @@
#include <gtest/gtest.h>

#include "frc/MathUtil.h"
#include "frc/geometry/Translation3d.h"
#include "frc/geometry/Translation2d.h"
#include "units/time.h"
#include "units/velocity.h"
#include "units/length.h"
#include "units/angle.h"

#define EXPECT_UNITS_EQ(a, b) EXPECT_DOUBLE_EQ((a).value(), (b).value())
Expand Down Expand Up @@ -164,3 +169,29 @@
EXPECT_FALSE(frc::IsNear(400, 395, 5, 0, 360));
EXPECT_FALSE(frc::IsNear(0_deg, -4_deg, 2.5_deg, 0_deg, 360_deg));
}

TEST(MathUtilTest, Translation2dSlewRateLimit) {
const frc::Translation2d translation1{0_m, 0_m};
const frc::Translation2d translation2{2_m, 2_m};
const frc::Translation2d translation3{1_m, 1_m};
const frc::Translation2d translation4{3_m, 3_m};
const frc::Translation2d result1 = frc::SlewRateLimit(translation1, translation2, 1_s, 50_mps);
const frc::Translation2d result2 = frc::SlewRateLimit(translation3, translation4, 0.25_s, 2_mps);
const frc::Translation2d expected1{2_m, 2_m};
const frc::Translation2d expected2{units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt2}, 1.0 + 0.5 * std::numbers::inv_sqrt2}, 1.0 + 0.5 * std::numbers::inv_sqrt2}};

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'inv_sqrt2': is not a member of 'std::numbers'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'inv_sqrt2': undeclared identifier

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'inv_sqrt2': is not a member of 'std::numbers'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'inv_sqrt2': undeclared identifier

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'initializing': cannot convert from 'initializer list' to 'frc::Translation2d'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

syntax error: 'constant'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

'inv_sqrt2': is not a member of 'std::numbers'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

syntax error: '}'

Check failure on line 181 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

syntax error: missing ';' before '}'
EXPECT_EQ(result1, expected1);

Check failure on line 182 in wpimath/src/test/native/cpp/MathUtilTest.cpp

View workflow job for this annotation

GitHub Actions / Build - Windows

syntax error: 'switch'
EXPECT_EQ(result2, expected2);
}

TEST(MathUtilTest, Translation3dSlewRateLimit) {
const frc::Translation3d translation1{0_m, 0_m, 0_m};
const frc::Translation3d translation2{2_m, 2_m, 2_m};
const frc::Translation3d translation3{1_m, 1_m, 1_m};
const frc::Translation3d translation4{3_m, 3_m, 3_m};
const frc::Translation3d result1 = frc::SlewRateLimit(translation1, translation2, 1_s, 50.0_mps);
const frc::Translation3d result2 = frc::SlewRateLimit(translation3, translation4, 0.25_s, 2.0_mps);
const frc::Translation3d expected1{2_m, 2_m, 2_m};
const frc::Translation3d expected2{units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}};
EXPECT_EQ(result1, expected1);
EXPECT_EQ(result2, expected2);
}
Loading