Class WsSparkMax


  • public class WsSparkMax
    extends WsMotorController
    Controls a Spark Max motor controller.
    • Constructor Summary

      Constructors 
      Constructor Description
      WsSparkMax​(java.lang.String name, int channel, boolean brushless, double p_default)
      Constructs the motor controller from config.
      WsSparkMax​(java.lang.String name, int channel, boolean brushless, double p_default, boolean invert)
      Constructs the motor controller from config.
    • Method Summary

      All Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      void addClosedLoop​(int slotID, double P, double I, double D, double FF)  
      void addFollower​(int canConstant, boolean brushless, boolean oppose)
      Add a follower motor to the current motor.
      void addFollower​(int canConstant, WsMotorControllers controller, boolean oppose)
      Add a follower motor to the current motor.
      void disableCurrentLimit()
      Does nothing, SparkMax has no current limit disable function.
      void enableVoltageCompensation()
      Enables voltage compensation.
      com.revrobotics.CANSparkMax getController()
      Returns the raw motor controller Object.
      com.revrobotics.CANSparkMax getFollower()
      Returns the raw follower motor controller Object.
      double getOutput()
      Returns the current motor output percent.
      com.revrobotics.SparkMaxPIDController getPIDController()  
      double getPosition()
      Returns the quadrature position from an encoder.
      double getTemperature()
      Returns the temperature of the motor.
      double getVelocity()
      Returns the quadrature velocity from an encoder.
      void initClosedLoop​(double P, double I, double D, double FF)
      Sets up closed loop control for the motor
      void initClosedLoop​(double P, double I, double D, double FF, com.revrobotics.AbsoluteEncoder absEncoder)
      Sets up closed loop control for the motor
      void initClosedLoop​(double P, double I, double D, double FF, com.revrobotics.AbsoluteEncoder absEncoder, boolean isWrapped)
      Sets up closed loop control for the motor
      void notifyConfigChange()
      Does nothing, config values only affects start state.
      void resetEncoder()
      Resets the position of an encoder.
      void sendDataToOutput()
      Sets motor control
      void setBrake()
      Sets the motor to brake mode, will not freely spin.
      void setCoast()
      Sets the motor to coast mode, will freely spin.
      void setCurrentLimit​(int stallLimitAmps, int freeLimitAmps, int limitRPM)
      Sets the current limit of the motor controller.
      void setPosition​(double target)
      Sets the motor to track the given position
      void setPosition​(double target, int slotID)
      Sets the motor to track the given position with a specific PIDFF constants
      void setSpeed​(double value)
      Wraps setValue().
      void setVelocity​(double target)
      Sets the motor to track the given velocity
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, notify, notifyAll, toString, wait, wait, wait
    • Constructor Detail

      • WsSparkMax

        public WsSparkMax​(java.lang.String name,
                          int channel,
                          boolean brushless,
                          double p_default)
        Constructs the motor controller from config.
        Parameters:
        name - Descriptive name of the controller.
        channel - Motor controller CAN constant.
        brushless - True if the motor is brushless, false if brushed.
        p_default - Default output value.
      • WsSparkMax

        public WsSparkMax​(java.lang.String name,
                          int channel,
                          boolean brushless,
                          double p_default,
                          boolean invert)
        Constructs the motor controller from config.
        Parameters:
        name - Descriptive name of the controller.
        channel - Motor controller CAN constant.
        brushless - True if the motor is brushless, false if brushed.
        p_default - Default output value.
        invert - Invert the motor's direction.
    • Method Detail

      • addFollower

        public void addFollower​(int canConstant,
                                boolean brushless,
                                boolean oppose)
        Add a follower motor to the current motor.
        Parameters:
        canConstant - CAN constant of the new follower motor.
        brushless - True if the motor is brushless, false if brushed.
        oppose - True if the follow should oppose the direction of this motor.
      • addFollower

        public void addFollower​(int canConstant,
                                WsMotorControllers controller,
                                boolean oppose)
        Add a follower motor to the current motor.
        Specified by:
        addFollower in class WsMotorController
        Parameters:
        canConstant - CAN constant of the new follower motor.
        controller - Enumeration representing type of controller.
        oppose - True if the follow should oppose the direction of this motor.
      • getController

        public com.revrobotics.CANSparkMax getController()
        Returns the raw motor controller Object.
        Specified by:
        getController in class WsMotorController
        Returns:
        CANSparkMax Object.
      • getFollower

        public com.revrobotics.CANSparkMax getFollower()
        Returns the raw follower motor controller Object.
        Specified by:
        getFollower in class WsMotorController
        Returns:
        Follower motor controller object, null if no follower.
      • setBrake

        public void setBrake()
        Sets the motor to brake mode, will not freely spin.
        Specified by:
        setBrake in class WsMotorController
      • setCoast

        public void setCoast()
        Sets the motor to coast mode, will freely spin.
        Specified by:
        setCoast in class WsMotorController
      • setCurrentLimit

        public void setCurrentLimit​(int stallLimitAmps,
                                    int freeLimitAmps,
                                    int limitRPM)
        Sets the current limit of the motor controller.
        Specified by:
        setCurrentLimit in class WsMotorController
        Parameters:
        stallLimitAmps - The amount of amps drawn before limiting while less than limitRPM.
        freeLimitAmps - The amount of amps drawn before limiting while greater than limitRPM.
        limitRPM - Sets the line between stallLimitAmps and freeLimitAmps.
      • enableVoltageCompensation

        public void enableVoltageCompensation()
        Enables voltage compensation.
      • getVelocity

        public double getVelocity()
        Returns the quadrature velocity from an encoder.
        Specified by:
        getVelocity in class WsMotorController
        Returns:
        Current velocity.
      • getPosition

        public double getPosition()
        Returns the quadrature position from an encoder.
        Specified by:
        getPosition in class WsMotorController
        Returns:
        Current position.
      • getOutput

        public double getOutput()
        Returns the current motor output percent.
        Specified by:
        getOutput in class WsMotorController
        Returns:
        Current motor output as a percent.
      • getTemperature

        public double getTemperature()
        Returns the temperature of the motor.
        Specified by:
        getTemperature in class WsMotorController
        Returns:
        Current temperature.
      • setSpeed

        public void setSpeed​(double value)
        Wraps setValue().
        Overrides:
        setSpeed in class WsMotorController
        Parameters:
        value - New motor percent speed, from -1.0 to 1.0.
      • initClosedLoop

        public void initClosedLoop​(double P,
                                   double I,
                                   double D,
                                   double FF)
        Sets up closed loop control for the motor
        Parameters:
        P - the P value
        I - the I value
        D - the D value
        FF - the feed forward constant
      • initClosedLoop

        public void initClosedLoop​(double P,
                                   double I,
                                   double D,
                                   double FF,
                                   com.revrobotics.AbsoluteEncoder absEncoder)
        Sets up closed loop control for the motor
        Parameters:
        P - the P value
        I - the I value
        D - the D value
        FF - the feed forward constant
        absEncoder - absolute encoder used to provided PID feedback
      • initClosedLoop

        public void initClosedLoop​(double P,
                                   double I,
                                   double D,
                                   double FF,
                                   com.revrobotics.AbsoluteEncoder absEncoder,
                                   boolean isWrapped)
        Sets up closed loop control for the motor
        Parameters:
        P - the P value
        I - the I value
        D - the D value
        FF - the feed forward constant
        absEncoder - absolute encoder used to provided PID feedback
        isWrapped - whether wrapping should be enabled
      • getPIDController

        public com.revrobotics.SparkMaxPIDController getPIDController()
      • addClosedLoop

        public void addClosedLoop​(int slotID,
                                  double P,
                                  double I,
                                  double D,
                                  double FF)
      • setPosition

        public void setPosition​(double target)
        Sets the motor to track the given position
        Parameters:
        target - the encoder target value to track to
      • setPosition

        public void setPosition​(double target,
                                int slotID)
        Sets the motor to track the given position with a specific PIDFF constants
        Parameters:
        target - the encoder target to track to
        slotID - the ID slot of the sparkmax to use
      • setVelocity

        public void setVelocity​(double target)
        Sets the motor to track the given velocity
        Parameters:
        target - the encoder target value velocity to track to
      • notifyConfigChange

        public void notifyConfigChange()
        Does nothing, config values only affects start state.
      • disableCurrentLimit

        public void disableCurrentLimit()
        Does nothing, SparkMax has no current limit disable function.
        Specified by:
        disableCurrentLimit in class WsMotorController