Package xbot.common.controls.actuators
Class XCANMotorController
java.lang.Object
xbot.common.controls.actuators.XCANMotorController
- All Implemented Interfaces:
DataFrameRefreshable
- Direct Known Subclasses:
CANSparkMaxWpiAdapter
,CANTalonFxWpiAdapter
,MockCANMotorController
-
Nested Class Summary
Modifier and TypeClassDescriptionstatic enum
The PID mode to use when setting a target position or velocity.static interface
-
Field Summary
Modifier and TypeFieldDescriptionprotected String
final CANBusId
final int
protected boolean
protected xbot.common.controls.io_inputs.XCANMotorControllerInputsAutoLogged
final PropertyFactory
protected boolean
-
Constructor Summary
ModifierConstructorDescriptionprotected
XCANMotorController
(CANMotorControllerInfo info, String owningSystemPrefix, PropertyFactory propertyFactory, DevicePolice police, String pidPropertyPrefix, XCANMotorControllerPIDProperties defaultPIDProperties) -
Method Summary
Modifier and TypeMethodDescriptionabstract double
getPower()
abstract boolean
void
periodic()
void
Consumes and processes inputs from the device or subsystem.abstract void
setClosedLoopRampRates
(Time dutyCyclePeriod, Time voltagePeriod) abstract void
setConfiguration
(CANMotorControllerOutputConfig outputConfig) abstract void
setOpenLoopRampRates
(Time dutyCyclePeriod, Time voltagePeriod) void
setPidDirectly
(double p, double i, double d) void
setPidDirectly
(double p, double i, double d, double velocityFF, double gravityFF) abstract void
setPidDirectly
(double p, double i, double d, double velocityFF, double gravityFF, int slot) void
setPosition
(Angle position) void
setPositionTarget
(Angle position, XCANMotorController.MotorPidMode mode) abstract void
setPositionTarget
(Angle position, XCANMotorController.MotorPidMode mode, int slot) abstract void
setPower
(double power) abstract void
setPowerRange
(double minPower, double maxPower) abstract void
setTrapezoidalProfileAcceleration
(AngularAcceleration acceleration) abstract void
void
setVelocityTarget
(AngularVelocity velocity) void
setVelocityTarget
(AngularVelocity velocity, XCANMotorController.MotorPidMode mode) abstract void
setVelocityTarget
(AngularVelocity velocity, XCANMotorController.MotorPidMode mode, int slot) protected abstract void
-
Field Details
-
busId
-
deviceId
public final int deviceId -
propertyFactory
-
inputs
protected xbot.common.controls.io_inputs.XCANMotorControllerInputsAutoLogged inputs -
akitName
-
usesPropertySystem
protected boolean usesPropertySystem -
firstPeriodicCall
protected boolean firstPeriodicCall
-
-
Constructor Details
-
XCANMotorController
protected XCANMotorController(CANMotorControllerInfo info, String owningSystemPrefix, PropertyFactory propertyFactory, DevicePolice police, String pidPropertyPrefix, XCANMotorControllerPIDProperties defaultPIDProperties)
-
-
Method Details
-
setConfiguration
-
setPidDirectly
public void setPidDirectly(double p, double i, double d) -
setPidDirectly
public void setPidDirectly(double p, double i, double d, double velocityFF, double gravityFF) -
setPidDirectly
public abstract void setPidDirectly(double p, double i, double d, double velocityFF, double gravityFF, int slot) -
periodic
public void periodic() -
setOpenLoopRampRates
-
setClosedLoopRampRates
-
setTrapezoidalProfileAcceleration
-
setTrapezoidalProfileJerk
-
setPower
public abstract void setPower(double power) -
getPower
public abstract double getPower() -
setPowerRange
public abstract void setPowerRange(double minPower, double maxPower) -
getPosition
-
setPosition
-
setPositionTarget
-
setPositionTarget
public abstract void setPositionTarget(Angle position, XCANMotorController.MotorPidMode mode, int slot) -
getVelocity
-
setVelocityTarget
-
setVelocityTarget
-
setVelocityTarget
public abstract void setVelocityTarget(AngularVelocity velocity, XCANMotorController.MotorPidMode mode, int slot) -
getVoltage
-
getCurrent
-
isInverted
public abstract boolean isInverted() -
updateInputs
-
refreshDataFrame
public void refreshDataFrame()Description copied from interface:DataFrameRefreshable
Consumes and processes inputs from the device or subsystem.- Specified by:
refreshDataFrame
in interfaceDataFrameRefreshable
-