Package trclib.motor

Interface TrcMotorController

All Known Implementing Classes:
FtcCRServo, FtcDcMotor, TrcMotor

public interface TrcMotorController
This interface implements a generic motor. Some motors natively support some of the methods but simulate others. Some methods may be unsupported by the motor in which case it may throw an UnsupportedOperationException.
  • Method Details

    • resetFactoryDefault

      void resetFactoryDefault()
      This method resets the motor controller configurations to factory default so that everything is at known state.
    • getBusVoltage

      double getBusVoltage()
      This method returns the bus voltage of the motor controller.
      Returns:
      bus voltage of the motor controller.
    • setCurrentLimit

      void setCurrentLimit(double currentLimit, double triggerThresholdCurrent, double triggerThresholdTime)
      This method sets the current limit of the motor.
      Parameters:
      currentLimit - specifies the current limit (holding current) in amperes when feature is activated.
      triggerThresholdCurrent - specifies threshold current in amperes to be exceeded before limiting occurs. If this value is less than currentLimit, then currentLimit is used as the threshold.
      triggerThresholdTime - specifies how long current must exceed threshold (seconds) before limiting occurs.
    • setStatorCurrentLimit

      void setStatorCurrentLimit(double currentLimit)
      This method sets the stator current limit of the motor.
      Parameters:
      currentLimit - specifies the stator current limit in amperes.
    • setCloseLoopRampRate

      void setCloseLoopRampRate(double rampTime)
      This method sets the close loop ramp rate.
      Parameters:
      rampTime - specifies the ramp time in seconds from neutral to full speed.
    • setOpenLoopRampRate

      void setOpenLoopRampRate(double rampTime)
      This method sets the open loop ramp rate.
      Parameters:
      rampTime - specifies the ramp time in seconds from neutral to full speed.
    • setBrakeModeEnabled

      void setBrakeModeEnabled(boolean enabled)
      This method enables/disables motor brake mode. In motor brake mode, set power to 0 would stop the motor very abruptly by shorting the motor wires together using the generated back EMF to stop the motor. When not enabled, (i.e. float/coast mode), the motor wires are just disconnected from the motor controller so the motor will stop gradually.
      Parameters:
      enabled - specifies true to enable brake mode, false otherwise.
    • enableMotorRevLimitSwitch

      void enableMotorRevLimitSwitch(boolean normalClose)
      This method enables the reverse limit switch and configures it to the specified type.
      Parameters:
      normalClose - specifies true as the normal close switch type, false as normal open.
    • enableMotorFwdLimitSwitch

      void enableMotorFwdLimitSwitch(boolean normalClose)
      This method enables the forward limit switch and configures it to the specified type.
      Parameters:
      normalClose - specifies true as the normal close switch type, false as normal open.
    • disableMotorRevLimitSwitch

      void disableMotorRevLimitSwitch()
      This method disables the reverse limit switch.
    • disableMotorFwdLimitSwitch

      void disableMotorFwdLimitSwitch()
      This method disables the forward limit switch.
    • isMotorRevLimitSwitchEnabled

      boolean isMotorRevLimitSwitchEnabled()
      This method checks if the reverse limit switch is enabled.
      Returns:
      true if enabled, false if disabled.
    • isMotorFwdLimitSwitchEnabled

      boolean isMotorFwdLimitSwitchEnabled()
      This method checks if the forward limit switch is enabled.
      Returns:
      true if enabled, false if disabled.
    • setMotorRevLimitSwitchInverted

      void setMotorRevLimitSwitchInverted(boolean inverted)
      This method inverts the active state of the reverse limit switch, typically reflecting whether the switch is wired normally open or normally close.
      Parameters:
      inverted - specifies true to invert the limit switch to normal close, false to normal open.
    • setMotorFwdLimitSwitchInverted

      void setMotorFwdLimitSwitchInverted(boolean inverted)
      This method inverts the active state of the forward limit switch, typically reflecting whether the switch is wired normally open or normally close.
      Parameters:
      inverted - specifies true to invert the limit switch to normal close, false to normal open.
    • isMotorRevLimitSwitchActive

      boolean isMotorRevLimitSwitchActive()
      This method returns the state of the reverse limit switch.
      Returns:
      true if reverse limit switch is active, false otherwise.
    • isMotorFwdLimitSwitchActive

      boolean isMotorFwdLimitSwitchActive()
      This method returns the state of the forward limit switch.
      Returns:
      true if forward limit switch is active, false otherwise.
    • setMotorRevSoftPositionLimit

      void setMotorRevSoftPositionLimit(Double limit)
      This method sets the soft position limit for the reverse direction.
      Parameters:
      limit - specifies the limit in sensor units, null to disable.
    • setMotorFwdSoftPositionLimit

      void setMotorFwdSoftPositionLimit(Double limit)
      This method sets the soft position limit for the forward direction.
      Parameters:
      limit - specifies the limit in sensor units, null to disable.
    • setMotorPositionSensorInverted

      void setMotorPositionSensorInverted(boolean inverted)
      This method inverts the position sensor direction. This may be rare but there are scenarios where the motor encoder may be mounted somewhere in the power train that it rotates opposite to the motor rotation. This will cause the encoder reading to go down when the motor is receiving positive power. This method can correct this situation.
      Parameters:
      inverted - specifies true to invert position sensor direction, false otherwise.
    • isMotorPositionSensorInverted

      boolean isMotorPositionSensorInverted()
      This method returns the state of the position sensor direction.
      Returns:
      true if the motor direction is inverted, false otherwise.
    • resetMotorPosition

      void resetMotorPosition()
      This method resets the motor position sensor, typically an encoder.
    • setMotorInverted

      void setMotorInverted(boolean inverted)
      This method inverts the spinning direction of the motor.
      Parameters:
      inverted - specifies true to invert motor direction, false otherwise.
    • isMotorInverted

      boolean isMotorInverted()
      This method checks if the motor direction is inverted.
      Returns:
      true if motor direction is inverted, false otherwise.
    • setMotorPower

      void setMotorPower(double power)
      This method sets the percentage motor power.
      Parameters:
      power - specifies the percentage power (range -1.0 to 1.0).
    • getMotorPower

      double getMotorPower()
      This method gets the current motor power.
      Returns:
      current motor power.
    • setMotorVelocity

      void setMotorVelocity(double velocity, double acceleration, double feedForward)
      This method commands the motor to spin at the given velocity using close loop control.
      Parameters:
      velocity - specifies the motor velocity in rotations per second.
      acceleration - specifies the max motor acceleration rotations per second square, can be 0 if not provided.
      feedForward - specifies feedforward in volts.
    • getMotorVelocity

      double getMotorVelocity()
      This method returns the current motor velocity.
      Returns:
      current motor velocity in raw sensor units per sec.
    • setMotorPosition

      void setMotorPosition(double position, Double powerLimit, double velocity, double feedForward)
      This method commands the motor to go to the given position using close loop control and optionally limits the power of the motor movement.
      Parameters:
      position - specifies the position in rotations.
      powerLimit - specifies the maximum power output limits, can be null if not provided. If not provided, the previous set limit is applied.
      velocity - specifies the max motor velocity rotations per second, can be 0 if not provided.
      feedForward - specifies feedforward in volts.
    • getMotorPosition

      double getMotorPosition()
      This method returns the motor position by reading the position sensor. The position sensor can be an encoder or a potentiometer.
      Returns:
      current motor position in sensor units.
    • setMotorCurrent

      void setMotorCurrent(double current)
      This method commands the motor to spin at the given current value using close loop control.
      Parameters:
      current - specifies current in amperes.
    • getMotorCurrent

      double getMotorCurrent()
      This method returns the motor current.
      Returns:
      motor current in amperes.
    • setMotorVelocityPidCoefficients

      void setMotorVelocityPidCoefficients(TrcPidController.PidCoefficients pidCoeff)
      This method sets the PID coefficients of the motor controller's velocity PID controller.
      Parameters:
      pidCoeff - specifies the PID coefficients to set.
    • getMotorVelocityPidCoefficients

      TrcPidController.PidCoefficients getMotorVelocityPidCoefficients()
      This method returns the PID coefficients of the motor controller's velocity PID controller.
      Returns:
      PID coefficients of the motor's veloicty PID controller.
    • setMotorPositionPidCoefficients

      void setMotorPositionPidCoefficients(TrcPidController.PidCoefficients pidCoeff)
      This method sets the PID coefficients of the motor controller's position PID controller.
      Parameters:
      pidCoeff - specifies the PID coefficients to set.
    • getMotorPositionPidCoefficients

      TrcPidController.PidCoefficients getMotorPositionPidCoefficients()
      This method returns the PID coefficients of the motor controller's position PID controller.
      Returns:
      PID coefficients of the motor's position PID controller.
    • setMotorCurrentPidCoefficients

      void setMotorCurrentPidCoefficients(TrcPidController.PidCoefficients pidCoeff)
      This method sets the PID coefficients of the motor controller's current PID controller.
      Parameters:
      pidCoeff - specifies the PID coefficients to set.
    • getMotorCurrentPidCoefficients

      TrcPidController.PidCoefficients getMotorCurrentPidCoefficients()
      This method returns the PID coefficients of the motor controller's current PID controller.
      Returns:
      PID coefficients of the motor's current PID controller.
    • setVoltageCompensationEnabled

      void setVoltageCompensationEnabled(Double batteryNominalVoltage)
      This method enables/disables voltage compensation so that it will maintain the motor output regardless of battery voltage.
      Parameters:
      batteryNominalVoltage - specifies the nominal voltage of the battery to enable, null to disable.
    • isVoltageCompensationEnabled

      boolean isVoltageCompensationEnabled()
      This method checks if voltage compensation is enabled.
      Returns:
      true if voltage compensation is enabled, false if disabled.
    • enableMotionProfile

      void enableMotionProfile(double velocity, double acceleration, double jerk)
      This method enables motion profile support.
      Parameters:
      velocity - specifies cruise velocity in the unit of rps.
      acceleration - specifies acceleration in the unit of rot per sec square.
      jerk - specifies acceleration derivation in the unit of rot per sec cube.
    • disableMotionProfile

      void disableMotionProfile()
      This method disables motion profile support.
    • follow

      void follow(TrcMotor motor, boolean inverted, double scale)
      This method sets this motor to follow another motor. Motor subclass should override this if it supports this natively. TrcMotor by default supports software follower list.
      Parameters:
      motor - specifies the motor to follow.
      inverted - specifies true if this motor is inverted from the motor it is following, false otherwise.
      scale - specifies the value scale for the follower motor, 1.0 by default.
    • getFollower

      TrcMotor getFollower(int index)
      This method returns the follower with the specified index.
      Parameters:
      index - specifies the follower index.
      Returns:
      follower.