DcMotor

open class DcMotor : DcMotorImpl, Ramping

Wrapper class for a DcMotor where all motor speed is passed through a configurable SmoothDamp function. This class is designed to be downcasted to the SDK DcMotor type.

Author

Lucas Bubner, 2024

Since

3.0.0

Constructors

Link copied to clipboard
constructor(motor: DcMotor)
Create a new Ramping DcMotor object, wrapping a DcMotor object and returning a new object that can be used in place of the original.
constructor(motor: DcMotor, smoothTime: Measure<Time>, maxDelta: Double)
Create a new Ramping DcMotor object, wrapping a DcMotor object and returning a new object that can be used in place of the original.

Inherited properties

Link copied to clipboard
protected open var controller: DcMotorController
Link copied to clipboard
protected open var direction: DcMotorSimple.Direction
Link copied to clipboard
protected open var motorType: MotorConfigurationType
Link copied to clipboard
protected open var portNumber: Int

Functions

Link copied to clipboard
Set the maximum change in power level per second.
Link copied to clipboard
open fun setPower(power: Double)
Set the power level of the motor, which will be passed through a SmoothDamp function defined by the motor's ramping parameters.
Link copied to clipboard
open fun setPowerInstant(power: Double)
Instantly set the power level of the motor, bypassing the SmoothDamp function.
Link copied to clipboard
Set whether the ramping function is enabled.
Link copied to clipboard
open fun setRampingParameters(smoothTime: Measure<Time>, maxDelta: Double): Ramping.DcMotor
Set the ramping parameters of the motor.
Link copied to clipboard
open fun setRampingTime(smoothTime: Measure<Time>): Ramping.DcMotor
Set the time it takes for the motor to reach the target power level.
Link copied to clipboard
open fun stop()
Instantly stop the motor, bypassing the SmoothDamp function.

Inherited functions

Link copied to clipboard
protected open fun adjustPosition(position: Int): Int
Link copied to clipboard
protected open fun adjustPower(power: Double): Double
Link copied to clipboard
open fun close()
Link copied to clipboard
Link copied to clipboard
open fun getController(): DcMotorController
Link copied to clipboard
Link copied to clipboard
open fun getDeviceName(): String
Link copied to clipboard
open fun getDirection(): DcMotorSimple.Direction
Link copied to clipboard
open fun getManufacturer(): HardwareDevice.Manufacturer
Link copied to clipboard
open fun getMode(): DcMotor.RunMode
Link copied to clipboard
open fun getMotorType(): MotorConfigurationType
Link copied to clipboard
protected open fun getOperationalDirection(): DcMotorSimple.Direction
Link copied to clipboard
open fun getPortNumber(): Int
Link copied to clipboard
open fun getPower(): Double
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
open fun getVersion(): Int
Link copied to clipboard
open fun getZeroPowerBehavior(): DcMotor.ZeroPowerBehavior
Link copied to clipboard
protected open fun internalSetMode(mode: DcMotor.RunMode)
Link copied to clipboard
protected open fun internalSetPower(power: Double)
Link copied to clipboard
protected open fun internalSetTargetPosition(position: Int)
Link copied to clipboard
open fun isBusy(): Boolean
Link copied to clipboard
open fun setDirection(direction: DcMotorSimple.Direction)
Link copied to clipboard
open fun setMode(mode: DcMotor.RunMode)
Link copied to clipboard
open fun setMotorType(motorType: MotorConfigurationType)
Link copied to clipboard
open fun setPowerFloat()
Link copied to clipboard
open fun setTargetPosition(position: Int)
Link copied to clipboard
open fun setZeroPowerBehavior(zeroPowerBehavior: DcMotor.ZeroPowerBehavior)