Package edu.wpi.first.math.kinematics
Class DifferentialDriveWheelPositions
java.lang.Object
edu.wpi.first.math.kinematics.DifferentialDriveWheelPositions
- All Implemented Interfaces:
Interpolatable<DifferentialDriveWheelPositions>,ProtobufSerializable,StructSerializable,WPISerializable
public class DifferentialDriveWheelPositions
extends Object
implements StructSerializable, ProtobufSerializable, Interpolatable<DifferentialDriveWheelPositions>
Represents the wheel positions for a differential drive drivetrain.
-
Field Summary
FieldsModifier and TypeFieldDescriptiondoubleDistance measured by the left side.static final DifferentialDriveWheelPositionsProtoDifferentialDriveWheelPositions struct for serialization.doubleDistance measured by the right side.static final DifferentialDriveWheelPositionsStructDifferentialDriveWheelPositions struct for serialization. -
Constructor Summary
ConstructorsConstructorDescriptionDifferentialDriveWheelPositions(double leftMeters, double rightMeters) Constructs a DifferentialDriveWheelPositions.DifferentialDriveWheelPositions(Distance left, Distance right) Constructs a DifferentialDriveWheelPositions. -
Method Summary
Modifier and TypeMethodDescriptionbooleaninthashCode()interpolate(DifferentialDriveWheelPositions endValue, double t) Return the interpolated value.toString()
-
Field Details
-
leftMeters
Distance measured by the left side. -
rightMeters
Distance measured by the right side. -
struct
DifferentialDriveWheelPositions struct for serialization. -
proto
DifferentialDriveWheelPositions struct for serialization.
-
-
Constructor Details
-
DifferentialDriveWheelPositions
Constructs a DifferentialDriveWheelPositions.- Parameters:
leftMeters- Distance measured by the left side.rightMeters- Distance measured by the right side.
-
DifferentialDriveWheelPositions
Constructs a DifferentialDriveWheelPositions.- Parameters:
left- Distance measured by the left side.right- Distance measured by the right side.
-
-
Method Details
-
equals
-
hashCode
-
toString
-
interpolate
public DifferentialDriveWheelPositions interpolate(DifferentialDriveWheelPositions endValue, double t) Description copied from interface:InterpolatableReturn the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolatein 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.
-