-
Notifications
You must be signed in to change notification settings - Fork 212
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Added scaling utilizing Vector2d which converts form cartesian coordi…
…nates to polar. Signed-off-by: thenetworkgrinch <[email protected]>
- Loading branch information
1 parent
b100007
commit 75996c9
Showing
7 changed files
with
141 additions
and
32 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,96 @@ | ||
package swervelib.math; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.math.geometry.Translation2d; | ||
|
||
/** | ||
* Vector containing Magnitude and Position | ||
*/ | ||
public class Vector2d | ||
{ | ||
|
||
/** | ||
* Position given as an angle {@link Rotation2d}. | ||
*/ | ||
public final Rotation2d position; | ||
/** | ||
* Arbitrary magnitude of the vector. | ||
*/ | ||
public final double magnitude; | ||
|
||
/** | ||
* Construct a Vector with a position and magnitude of 0. | ||
*/ | ||
public Vector2d() | ||
{ | ||
position = new Rotation2d(); | ||
magnitude = 0; | ||
} | ||
|
||
/** | ||
* Create a vector based off of the given {@link Translation2d}. The magnitude is the | ||
* {@link Math#hypot(double, double)} of the X and Y. | ||
* | ||
* @param cartesian {@link Translation2d} with the X and Y set. | ||
*/ | ||
public Vector2d(Translation2d cartesian) | ||
{ | ||
position = cartesian.getAngle(); | ||
magnitude = cartesian.getNorm(); | ||
} | ||
|
||
/** | ||
* Construct a {@link Vector2d} given the position and magnitude. | ||
* | ||
* @param position Position as a {@link Rotation2d}. | ||
* @param magnitude Magnitude as a double. | ||
*/ | ||
public Vector2d(Rotation2d position, double magnitude) | ||
{ | ||
this.position = position; | ||
this.magnitude = magnitude; | ||
} | ||
|
||
/** | ||
* Convert cartesian coordinates to Vector. | ||
* | ||
* @param x X position | ||
* @param y Y position | ||
*/ | ||
public Vector2d(double x, double y) | ||
{ | ||
this(new Translation2d(x, y)); | ||
} | ||
|
||
/** | ||
* Convert the Vector back into cartesian coordinates. | ||
* | ||
* @return {@link Translation2d} of the vector. | ||
*/ | ||
public Translation2d getTranslation() | ||
{ | ||
return new Translation2d(magnitude, position); | ||
} | ||
|
||
/** | ||
* Scale the magnitude by the multiplier given | ||
* | ||
* @param scalar Multiplier of the magnitude. | ||
* @return {@link Vector2d} for chained functions. | ||
*/ | ||
public Vector2d scale(double scalar) | ||
{ | ||
return new Vector2d(position, magnitude * scalar); | ||
} | ||
|
||
/** | ||
* Exponentially modify the magnitude. | ||
* | ||
* @param pow Power for the magnitude | ||
* @return {@link Vector2d} with the magnitude^pow | ||
*/ | ||
public Vector2d pow(double pow) | ||
{ | ||
return new Vector2d(position, Math.pow(this.magnitude, pow)); | ||
} | ||
} |