Class XCANMotorController

java.lang.Object
xbot.common.controls.actuators.XCANMotorController
All Implemented Interfaces:
DataFrameRefreshable
Direct Known Subclasses:
CANSparkMaxWpiAdapter, CANTalonFxWpiAdapter, MockCANMotorController

public abstract class XCANMotorController extends Object implements DataFrameRefreshable
  • Field Details

    • busId

      public final CANBusId busId
    • deviceId

      public final int deviceId
    • propertyFactory

      public final PropertyFactory propertyFactory
    • inputs

      protected xbot.common.controls.io_inputs.XCANMotorControllerInputsAutoLogged inputs
    • akitName

      protected String akitName
    • usesPropertySystem

      protected boolean usesPropertySystem
    • firstPeriodicCall

      protected boolean firstPeriodicCall
  • Constructor Details

  • Method Details

    • setConfiguration

      public abstract void setConfiguration(CANMotorControllerOutputConfig outputConfig)
    • 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

      public abstract void setOpenLoopRampRates(Time dutyCyclePeriod, Time voltagePeriod)
    • setClosedLoopRampRates

      public abstract void setClosedLoopRampRates(Time dutyCyclePeriod, Time voltagePeriod)
    • setTrapezoidalProfileAcceleration

      public abstract void setTrapezoidalProfileAcceleration(AngularAcceleration acceleration)
    • setTrapezoidalProfileJerk

      public abstract void setTrapezoidalProfileJerk(Velocity<AngularAccelerationUnit> jerk)
    • setPower

      public abstract void setPower(double power)
    • getPower

      public abstract double getPower()
    • setPowerRange

      public abstract void setPowerRange(double minPower, double maxPower)
    • getPosition

      public Angle getPosition()
    • setPosition

      public void setPosition(Angle position)
    • setPositionTarget

      public void setPositionTarget(Angle position, XCANMotorController.MotorPidMode mode)
    • setPositionTarget

      public abstract void setPositionTarget(Angle position, XCANMotorController.MotorPidMode mode, int slot)
    • getVelocity

      public AngularVelocity getVelocity()
    • setVelocityTarget

      public void setVelocityTarget(AngularVelocity velocity)
    • setVelocityTarget

      public void setVelocityTarget(AngularVelocity velocity, XCANMotorController.MotorPidMode mode)
    • setVelocityTarget

      public abstract void setVelocityTarget(AngularVelocity velocity, XCANMotorController.MotorPidMode mode, int slot)
    • getVoltage

      public Voltage getVoltage()
    • getCurrent

      public Current getCurrent()
    • isInverted

      public abstract boolean isInverted()
    • updateInputs

      protected abstract void updateInputs(XCANMotorControllerInputs inputs)
    • refreshDataFrame

      public void refreshDataFrame()
      Description copied from interface: DataFrameRefreshable
      Consumes and processes inputs from the device or subsystem.
      Specified by:
      refreshDataFrame in interface DataFrameRefreshable