Skip to content

[wpimath] Add copySignPow to MathUtil for joystick input shaping #8013

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

Merged
merged 21 commits into from
Jun 15, 2025

Conversation

MichaelLesirge
Copy link
Contributor

@MichaelLesirge MichaelLesirge commented Jun 9, 2025

EDIT: Name of method has been updated to copySignPow

This PR adds the simple util method of applyPowerCurve(value, exponent, maxMagnitude) to the Java and C++ MathUtil classes. This method transforms value to be on the power curve of x to the exponent while keeping its sign. It also handles a maxMagninude value that is used to keep the curve consistent (and the value in range) whether value is between the default of [-1,1] or some other magnitude like [-100,100].

Usage:

final double MAX_SPEED = 12.3;

double value = xbox.getLeftX() * MAX_SPEED; // get value from joystick

value = MathUtil.applyDeadband(value, 0.05, MAX_SPEED); // handle deadzone, filters speeds under 0.05

value = MathUtil.applyPowerCurve(value, 2.0, MAX_SPEED); // place the value on the curve of x^2 while keeping it in range and keeping it's direction

This technique is commonly used in to improve fine control at low speeds and enable quicker ramp-up at higher joystick deflections, most often with an exponent of 2 (squaring the input).

Including this function in MathUtil puts both commonly used joystick input transformations in one location and makes them easier for new teams to find and use.

This PR also updates the DifferentialDrive class to use applyPowerCurve in place of its previous manual implementation.

Feedback is appreciated, particularly on the method name and documentation comment, as well as better ways to implement this in C++ without calling .value() on unit types. This is my first time trying to add an actually new feature, mostly for the learning experience. I hope it’s a useful addition!

@MichaelLesirge MichaelLesirge requested a review from a team as a code owner June 9, 2025 06:43
@KangarooKoala
Copy link
Contributor

The current C++ units library doesn't support fractional exponents, so I think we do have to use .value().

Copy link
Contributor

@KangarooKoala KangarooKoala left a comment

Choose a reason for hiding this comment

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

Thanks for the detailed PR comment! (Though the example snippet includes redeclarations of the same variable (which isn't allowed) and a usage of the non-existent valueWithDeadband)

Overall, the code seems fine to me, but you'll need approval from an official WPILib maintainer.

@MichaelLesirge
Copy link
Contributor Author

Thanks for the detailed PR comment! (Though the example snippet includes redeclarations of the same variable (which isn't allowed) and a usage of the non-existent valueWithDeadband)

Whoops! Decided half way through writing the snippet to rename them all to just value and forgot to edit the rest lol. Edited to fix that up.

Thanks for the review!

@MichaelLesirge MichaelLesirge requested a review from calcmogul June 13, 2025 07:56
@bryceroethel
Copy link
Contributor

bryceroethel commented Jun 13, 2025

One thing to note when applying power curves to individual joystick axes with the intention of using their output for controlling a drivetrain (or other systems that use 2 axes), assuming your controller's joystick profile is a circle you will "lose" power output when the joystick is pointed at a diagonal. The transformed profile will turn into more of a funky "+" shape at higher exponent values.

Here's a very quick and dirty example of what happens with a joystick pointed at 45 degrees. X axis is the exponent, Y is the resulting norm (1 is the desired value for Y).

image

Not sure if implementing something that accounts for this is in the scope of this PR, but I figured I'd mention it since the primary use-case here seems to be drivetrain control. The solution involves multiplying each axis by their norm^(exponent - 1).

double x = hid.getLeftX();
double y = hid.getLeftY();

double multiplier = Math.pow(Math.hypot(x, y), exponent - 1.0);
x *= multiplier;
y *= multiplier;

@MichaelLesirge
Copy link
Contributor Author

MichaelLesirge commented Jun 13, 2025

One thing to note when applying power curves to individual joystick axes with the intention of using their output for controlling a drivetrain (or other systems that use 2 axes), assuming your controller's joystick profile is a circle you will "lose" power output when the joystick is pointed at a diagonal.

That is a good catch. In our own code base for our teams robot we do something kinda similar (doing deadband on the norm than squaring the norm). I have been working my way through a list that I kept of a bunch of small features that I would have loved to have in WPILib. I wanted to add this method first, and then see about adding Translation2d versions of applyDeadband and this method in a new PR if this one gets approved.

Very helpful graph by the way!

@MichaelLesirge MichaelLesirge changed the title [wpimath] Add applyPowerCurve to MathUtil for joystick input shaping [wpimath] Add copySignPow to MathUtil for joystick input shaping Jun 13, 2025
Copy link
Contributor

@KangarooKoala KangarooKoala left a comment

Choose a reason for hiding this comment

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

Looks good to me, for what it's worth.

@PeterJohnson PeterJohnson merged commit fb399ee into wpilibsuite:main Jun 15, 2025
44 checks passed
@MichaelLesirge MichaelLesirge deleted the math-ramp-up-util branch June 15, 2025 21:10
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants