Package ftclib.motor

Class FtcCRServo

java.lang.Object
trclib.motor.TrcMotor
ftclib.motor.FtcCRServo
All Implemented Interfaces:
TrcMotorController, TrcExclusiveSubsystem, TrcOdometrySensor

public class FtcCRServo extends TrcMotor
This class implements an FTC Continuous Rotation Servo extending TrcMotor. It provides implementation of the TrcMotorController interface in TrcMotor. It supports limit switches and an external position sensor (e.g. encoder). When this class is constructed with limit switches, all motor movements will respect them and will not move the motor into the direction where the limit switch is activated.
  • Field Details

    • servo

      public final com.qualcomm.robotcore.hardware.CRServoImplEx servo
    • voltageSensor

      private final com.qualcomm.robotcore.hardware.VoltageSensor voltageSensor
  • Constructor Details

    • FtcCRServo

      public FtcCRServo(com.qualcomm.robotcore.hardware.HardwareMap hardwareMap, String instanceName, TrcMotor.ExternalSensors sensors)
      Constructor: Create an instance of the object.
      Parameters:
      hardwareMap - specifies the global hardware map.
      instanceName - specifies the instance name of the servo.
      sensors - specifies external sensors, can be null if none.
    • FtcCRServo

      public FtcCRServo(String instanceName, TrcMotor.ExternalSensors sensors)
      Constructor: Create an instance of the object.
      Parameters:
      instanceName - specifies the instance name of the servo.
      sensors - specifies external sensors, can be null if none.
    • FtcCRServo

      public FtcCRServo(String instanceName)
      Constructor: Create an instance of the object.
      Parameters:
      instanceName - specifies the instance name of the servo.
  • Method Details

    • resetFactoryDefault

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

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

      public 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

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

      public 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

      public 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

      public 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

      public 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

      public 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

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

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

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

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

      public 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

      public 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

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

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

      public 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

      public 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

      public 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

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

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

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

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

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

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

      public 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

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

      public 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

      public double getMotorPosition()
      This method returns the motor position by reading the position sensor.
      Returns:
      current motor position in raw sensor units.
    • setMotorCurrent

      public 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

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

      public 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

      public 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

      public 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

      public 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

      public 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

      public 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.