Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.geometry.Rotation2d Class Reference
Inheritance diagram for edu.wpi.first.math.geometry.Rotation2d:
edu.wpi.first.math.interpolation.Interpolatable< T > edu.wpi.first.util.protobuf.ProtobufSerializable edu.wpi.first.util.struct.StructSerializable edu.wpi.first.util.WPISerializable edu.wpi.first.util.WPISerializable

Public Member Functions

 Rotation2d ()
 
 Rotation2d (@JsonProperty(required=true, value="radians") double value)
 
 Rotation2d (double x, double y)
 
 Rotation2d (Measure< Angle > angle)
 
Rotation2d plus (Rotation2d other)
 
Rotation2d minus (Rotation2d other)
 
Rotation2d unaryMinus ()
 
Rotation2d times (double scalar)
 
Rotation2d div (double scalar)
 
Rotation2d rotateBy (Rotation2d other)
 
double getRadians ()
 
double getDegrees ()
 
double getRotations ()
 
double getCos ()
 
double getSin ()
 
double getTan ()
 
boolean equals (Object obj)
 
- Public Member Functions inherited from edu.wpi.first.math.interpolation.Interpolatable< T >
interpolate (T endValue, double t)
 

Static Public Member Functions

static Rotation2d fromRadians (double radians)
 
static Rotation2d fromDegrees (double degrees)
 
static Rotation2d fromRotations (double rotations)
 

Static Public Attributes

static final Rotation2dProto proto = new Rotation2dProto()
 
static final Rotation2dStruct struct = new Rotation2dStruct()
 

Detailed Description

A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).

The angle is continuous, that is if a Rotation2d is constructed with 361 degrees, it will return 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the rotations as it sweeps past from 360 to 0 on the second time around.

Constructor & Destructor Documentation

◆ Rotation2d() [1/4]

edu.wpi.first.math.geometry.Rotation2d.Rotation2d ( )

Constructs a Rotation2d with a default angle of 0 degrees.

◆ Rotation2d() [2/4]

edu.wpi.first.math.geometry.Rotation2d.Rotation2d ( @JsonProperty(required=true, value="radians") double value)

Constructs a Rotation2d with the given radian value.

Parameters
valueThe value of the angle in radians.

◆ Rotation2d() [3/4]

edu.wpi.first.math.geometry.Rotation2d.Rotation2d ( double x,
double y )

Constructs a Rotation2d with the given x and y (cosine and sine) components.

Parameters
xThe x component or cosine of the rotation.
yThe y component or sine of the rotation.

◆ Rotation2d() [4/4]

edu.wpi.first.math.geometry.Rotation2d.Rotation2d ( Measure< Angle > angle)

Constructs a Rotation2d with the given angle.

Parameters
angleThe angle of the rotation.

Member Function Documentation

◆ div()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.div ( double scalar)

Divides the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ equals()

boolean edu.wpi.first.math.geometry.Rotation2d.equals ( Object obj)

Checks equality between this Rotation2d and another object.

Parameters
objThe other object.
Returns
Whether the two objects are equal or not.

◆ fromDegrees()

static Rotation2d edu.wpi.first.math.geometry.Rotation2d.fromDegrees ( double degrees)
static

Constructs and returns a Rotation2d with the given degree value.

Parameters
degreesThe value of the angle in degrees.
Returns
The rotation object with the desired angle value.

◆ fromRadians()

static Rotation2d edu.wpi.first.math.geometry.Rotation2d.fromRadians ( double radians)
static

Constructs and returns a Rotation2d with the given radian value.

Parameters
radiansThe value of the angle in radians.
Returns
The rotation object with the desired angle value.

◆ fromRotations()

static Rotation2d edu.wpi.first.math.geometry.Rotation2d.fromRotations ( double rotations)
static

Constructs and returns a Rotation2d with the given number of rotations.

Parameters
rotationsThe value of the angle in rotations.
Returns
The rotation object with the desired angle value.

◆ getCos()

double edu.wpi.first.math.geometry.Rotation2d.getCos ( )

Returns the cosine of the Rotation2d.

Returns
The cosine of the Rotation2d.

◆ getDegrees()

double edu.wpi.first.math.geometry.Rotation2d.getDegrees ( )

Returns the degree value of the Rotation2d.

Returns
The degree value of the Rotation2d.
See also
edu.wpi.first.math.MathUtil.inputModulus(double, double, double) to constrain the angle within (-180, 180]

◆ getRadians()

double edu.wpi.first.math.geometry.Rotation2d.getRadians ( )

Returns the radian value of the Rotation2d.

Returns
The radian value of the Rotation2d.
See also
edu.wpi.first.math.MathUtil.angleModulus(double) to constrain the angle within (-pi, pi]

◆ getRotations()

double edu.wpi.first.math.geometry.Rotation2d.getRotations ( )

Returns the number of rotations of the Rotation2d.

Returns
The number of rotations of the Rotation2d.

◆ getSin()

double edu.wpi.first.math.geometry.Rotation2d.getSin ( )

Returns the sine of the Rotation2d.

Returns
The sine of the Rotation2d.

◆ getTan()

double edu.wpi.first.math.geometry.Rotation2d.getTan ( )

Returns the tangent of the Rotation2d.

Returns
The tangent of the Rotation2d.

◆ minus()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.minus ( Rotation2d other)

Subtracts the new rotation from the current rotation and returns the new rotation.

For example, Rotation2d.fromDegrees(10).minus(Rotation2d.fromDegrees(100)) equals Rotation2d(-Math.PI/2.0)

Parameters
otherThe rotation to subtract.
Returns
The difference between the two rotations.

◆ plus()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.plus ( Rotation2d other)

Adds two rotations together, with the result being bounded between -pi and pi.

For example, Rotation2d.fromDegrees(30).plus(Rotation2d.fromDegrees(60)) equals Rotation2d(Math.PI/2.0)

Parameters
otherThe rotation to add.
Returns
The sum of the two rotations.

◆ rotateBy()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.rotateBy ( Rotation2d other)

Adds the new rotation to the current rotation using a rotation matrix.

The matrix multiplication is as follows:

[cos_new]   [other.cos, -other.sin][cos]
[sin_new] = [other.sin,  other.cos][sin]
value_new = atan2(sin_new, cos_new)
Parameters
otherThe rotation to rotate by.
Returns
The new rotated Rotation2d.

◆ times()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.times ( double scalar)

Multiplies the current rotation by a scalar.

Parameters
scalarThe scalar.
Returns
The new scaled Rotation2d.

◆ unaryMinus()

Rotation2d edu.wpi.first.math.geometry.Rotation2d.unaryMinus ( )

Takes the inverse of the current rotation. This is simply the negative of the current angular value.

Returns
The inverse of the current rotation.

Member Data Documentation

◆ proto

final Rotation2dProto edu.wpi.first.math.geometry.Rotation2d.proto = new Rotation2dProto()
static

Rotation2d protobuf for serialization.

◆ struct

final Rotation2dStruct edu.wpi.first.math.geometry.Rotation2d.struct = new Rotation2dStruct()
static

Rotation2d struct for serialization.


The documentation for this class was generated from the following file: