Motor

class Motor @JvmOverloads constructor(motor: DcMotorEx, val maxRPM: Double, val TPR: Double = 1.0, clock: NanoClock = NanoClock.system) : Component

A wrapper for the DcMotorEx object in the FTC SDK.

Parameters

motor

The motor for the wrapper to use.

maxRPM

The maximum revolutions per minute of the motor.

TPR

The ticks per revolution of the motor.

Constructors

Link copied to clipboard
constructor(hMap: HardwareMap, id: String, maxRPM: Double, TPR: Double = 1.0, clock: NanoClock = NanoClock.system)
constructor(hMap: HardwareMap, id: String, type: Motor.Type, clock: NanoClock = NanoClock.system)
constructor(motor: DcMotorEx, type: Motor.Type, clock: NanoClock = NanoClock.system)
constructor(motor: DcMotorEx, maxRPM: Double, TPR: Double = 1.0, clock: NanoClock = NanoClock.system)

Types

Link copied to clipboard
class Encoder

A wrapper for motor encoders in the FTC SDK.

Link copied to clipboard
Link copied to clipboard

A class with the specs of many motors so you don't have to find them.

Properties

Link copied to clipboard

The current position of the encoder (in ticks).

Link copied to clipboard

The distance travelled by the motor. Computed using the encoder and distancePerTick.

Link copied to clipboard

The distance per revolution travelled by the motor.

Link copied to clipboard

The velocity of the motor in distance per second. Computed using the encoder and distancePerTick.

Link copied to clipboard
Link copied to clipboard

Feedforward used in RunMode.RUN_USING_ENCODER and optionally RunMode.RUN_WITHOUT_ENCODER. Note that these coefficients are applied to desired encoder tick velocity. This must be tuned in order for setTickVelocity, setDistanceVelocity, and setRPM to work.

Link copied to clipboard
val internal: DcMotorEx
Link copied to clipboard

The maximum achievable distance velocity of the motor, in units per second. Computed using maxTPS and distancePerTick.

Link copied to clipboard
Link copied to clipboard

The maximum achievable ticks per second of the motor. Computed using maxRPM and TPR.

Link copied to clipboard

The percentage of power to the motor in the range [-1.0, 1.0].

Link copied to clipboard
@get:JvmName(name = "isReversed")
var reversed: Boolean

Whether the motor is reversed.

Link copied to clipboard

The total rotation of the motor. Note that this value is positive or negative according to motor direction.

Link copied to clipboard
Link copied to clipboard

The target velocity of RunMode.RUN_USING_ENCODER in ticks per second.

Link copied to clipboard
val TPR: Double = 1.0
Link copied to clipboard

The velocity of the motor, in ticks per second. Computed using the encoder.

Link copied to clipboard

Functions

Link copied to clipboard

Resets the encoder.

Link copied to clipboard

Reverses the direction of the motor.

Link copied to clipboard
fun setDistanceVelocity(velocity: Double, acceleration: Double = 0.0)

Sets the velocity of the motor in distance units per second.

Link copied to clipboard
fun setReversed(reversed: Boolean): Motor
Link copied to clipboard
fun setRPM(rpm: Double)

Sets the velocity of the motor in revolutions per second.

Link copied to clipboard
fun setTickVelocity(velocity: Double, acceleration: Double = 0.0)

Sets the velocity of the motor in encoder ticks per second.

Link copied to clipboard
open override fun update()

Updates both RunMode.RUN_USING_ENCODER and RunMode.RUN_TO_POSITION. Running this method is not necessary for RunMode.RUN_WITHOUT_ENCODER.