Package edu.wpi.first.math.kinematics
Class DifferentialDriveWheelPositions
java.lang.Object
edu.wpi.first.math.kinematics.DifferentialDriveWheelPositions
- All Implemented Interfaces:
Interpolatable<DifferentialDriveWheelPositions>
,WheelPositions<DifferentialDriveWheelPositions>
public class DifferentialDriveWheelPositions extends Object implements WheelPositions<DifferentialDriveWheelPositions>
-
Field Summary
Fields Modifier and Type Field Description double
leftMeters
Distance measured by the left side.double
rightMeters
Distance measured by the right side. -
Constructor Summary
Constructors Constructor Description DifferentialDriveWheelPositions(double leftMeters, double rightMeters)
Constructs a DifferentialDriveWheelPositions. -
Method Summary
Modifier and Type Method Description DifferentialDriveWheelPositions
copy()
Returns a copy of this instance.boolean
equals(Object obj)
int
hashCode()
DifferentialDriveWheelPositions
interpolate(DifferentialDriveWheelPositions endValue, double t)
Return the interpolated value.DifferentialDriveWheelPositions
minus(DifferentialDriveWheelPositions other)
Returns the difference with another set of wheel positions.String
toString()
-
Field Details
-
leftMeters
Distance measured by the left side. -
rightMeters
Distance measured by the right side.
-
-
Constructor Details
-
DifferentialDriveWheelPositions
Constructs a DifferentialDriveWheelPositions.- Parameters:
leftMeters
- Distance measured by the left side.rightMeters
- Distance measured by the right side.
-
-
Method Details
-
equals
-
hashCode
-
toString
-
copy
Description copied from interface:WheelPositions
Returns a copy of this instance.- Specified by:
copy
in interfaceWheelPositions<DifferentialDriveWheelPositions>
- Returns:
- A copy.
-
minus
Description copied from interface:WheelPositions
Returns the difference with another set of wheel positions.- Specified by:
minus
in interfaceWheelPositions<DifferentialDriveWheelPositions>
- Parameters:
other
- The other instance to compare to.- Returns:
- The representation of how the wheels moved from other to this.
-
interpolate
public DifferentialDriveWheelPositions interpolate(DifferentialDriveWheelPositions endValue, double t)Description copied from interface:Interpolatable
Return the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolate
in interfaceInterpolatable<DifferentialDriveWheelPositions>
- Parameters:
endValue
- The upper bound, or end.t
- How far between the lower and upper bound we are. This should be bounded in [0, 1].- Returns:
- The interpolated value.
-