Class WsPhoenix
- java.lang.Object
-
- org.wildstang.framework.io.outputs.Output
-
- org.wildstang.framework.io.outputs.AnalogOutput
-
- org.wildstang.hardware.roborio.outputs.WsMotorController
-
- org.wildstang.hardware.roborio.outputs.WsPhoenix
-
public class WsPhoenix extends WsMotorController
Controls a Talon or Victor motor controller as a Phoenix BaseMotorController.
-
-
Constructor Summary
Constructors Constructor Description WsPhoenix(java.lang.String name, int channel, double p_default, WsMotorControllers controller, boolean invert)Constructs the motor controller from config.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidaddFollower(int canConstant, WsMotorControllers controller, boolean oppose)Add a follower motor to the current motor.voiddisableCurrentLimit()Disables the current limit of the motor controller.voidenableProfile(boolean enable)Enables or disables motion profile.voidfillProfile(java.util.ArrayList<com.ctre.phoenix.motion.TrajectoryPoint> points)Fills the motor controllers path buffers with the upcoming points.com.ctre.phoenix.motorcontrol.can.BaseMotorControllergetController()Returns the raw motor controller Object.WsMotorControllersgetControllerType()Determines the type of motor controller represented.com.ctre.phoenix.motorcontrol.can.BaseMotorControllergetFollower()Returns the raw follower motor controller Object.doublegetOutput()Returns the current motor output percent.doublegetPosition()Returns the quadrature position from a Talon's encoder.com.ctre.phoenix.motion.MotionProfileStatusgetProfileStatus()Get the motor controller's motion profile status.doublegetTemperature()Return the motor controller temperaturedoublegetVelocity()Returns the quadrature velocity from a Talon's encoder.voidholdPosition(int slot)Actively holds a given position, useful for braking.intlimitSwitchState()Returns the state of a Talon's limit switches.voidnotifyConfigChange()Does nothing, config values only affects start state.voidresetEncoder()Resets the position of a Talon's encoder.voidsendDataToOutput()Sets motor speed to current value, from -1.0 to 1.0.voidsetBrake()Sets the motor to brake mode, will not freely spin.voidsetCoast()Sets the motor to coast mode, will freely spin.voidsetCurrentLimit(int peakLimitAmps, int peakDuractionMs, int continuousLimitAmps)Sets the current limit of the motor controller.voidsetMotionControlFramePeriod(int period)Sets the motion profiles control frame period.voidsetProfile(int slot)Sets and runs the motion profile slot to use.voidupdateProfile()Processes the current motion profile's buffer.-
Methods inherited from class org.wildstang.hardware.roborio.outputs.WsMotorController
setSpeed, stop
-
Methods inherited from class org.wildstang.framework.io.outputs.AnalogOutput
getValue, setValue
-
-
-
-
Constructor Detail
-
WsPhoenix
public WsPhoenix(java.lang.String name, int channel, double p_default, WsMotorControllers controller, boolean invert)Constructs the motor controller from config.- Parameters:
name- Descriptive name of the controller.channel- Motor controller CAN constant.p_default- Default output value.controller- Enumeration representing type of controller.invert- Invert the motor's direction.
-
-
Method Detail
-
addFollower
public void addFollower(int canConstant, WsMotorControllers controller, boolean oppose)Add a follower motor to the current motor.- Specified by:
addFollowerin classWsMotorController- 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.ctre.phoenix.motorcontrol.can.BaseMotorController getController()
Returns the raw motor controller Object.- Specified by:
getControllerin classWsMotorController- Returns:
- CANSparkMax Object.
-
getFollower
public com.ctre.phoenix.motorcontrol.can.BaseMotorController getFollower()
Returns the raw follower motor controller Object.- Specified by:
getFollowerin classWsMotorController- Returns:
- Follower motor controller object, null if no follower.
-
getControllerType
public WsMotorControllers getControllerType()
Determines the type of motor controller represented.- Returns:
- Enumeration representing type of motor controller.
-
setBrake
public void setBrake()
Sets the motor to brake mode, will not freely spin.- Specified by:
setBrakein classWsMotorController
-
setCoast
public void setCoast()
Sets the motor to coast mode, will freely spin.- Specified by:
setCoastin classWsMotorController
-
setCurrentLimit
public void setCurrentLimit(int peakLimitAmps, int peakDuractionMs, int continuousLimitAmps)Sets the current limit of the motor controller. Only Talons support current limiting.- Specified by:
setCurrentLimitin classWsMotorController- Parameters:
peakLimitAmps- The instantaneous amount of amps drawn before limiting.peakDuractionMs- The amount of time peakLimitAmps must be broken before limiting, in milliseconds.continuousLimitAmps- The continuous amount of amps drawn before limiting, normally less than peakLimitAmps.
-
disableCurrentLimit
public void disableCurrentLimit()
Disables the current limit of the motor controller. Only Talons support current limiting.- Specified by:
disableCurrentLimitin classWsMotorController
-
getVelocity
public double getVelocity()
Returns the quadrature velocity from a Talon's encoder.- Specified by:
getVelocityin classWsMotorController- Returns:
- Current velocity, 0 if not a Talon.
-
getPosition
public double getPosition()
Returns the quadrature position from a Talon's encoder.- Specified by:
getPositionin classWsMotorController- Returns:
- Current position, 0 if not a Talon.
-
resetEncoder
public void resetEncoder()
Resets the position of a Talon's encoder.- Specified by:
resetEncoderin classWsMotorController
-
limitSwitchState
public int limitSwitchState()
Returns the state of a Talon's limit switches.- Returns:
- Returns 1 if the forward limit switch is closed, 0 if neither or both, and -1 if the reverse limit switch is closed.
-
setProfile
public void setProfile(int slot)
Sets and runs the motion profile slot to use.- Parameters:
slot- Motion profile slot number.
-
enableProfile
public void enableProfile(boolean enable)
Enables or disables motion profile.- Parameters:
enable- True if to enable profile.
-
getProfileStatus
public com.ctre.phoenix.motion.MotionProfileStatus getProfileStatus()
Get the motor controller's motion profile status.- Returns:
- Status of the motion profile.
-
fillProfile
public void fillProfile(java.util.ArrayList<com.ctre.phoenix.motion.TrajectoryPoint> points)
Fills the motor controllers path buffers with the upcoming points.- Parameters:
points- List of upcoming trajectories.
-
updateProfile
public void updateProfile()
Processes the current motion profile's buffer.
-
setMotionControlFramePeriod
public void setMotionControlFramePeriod(int period)
Sets the motion profiles control frame period.- Parameters:
period- Time in milliseconds.
-
holdPosition
public void holdPosition(int slot)
Actively holds a given position, useful for braking.- Parameters:
slot- Motion profile slot number.
-
getOutput
public double getOutput()
Returns the current motor output percent.- Specified by:
getOutputin classWsMotorController- Returns:
- Current motor output as a percent.
-
getTemperature
public double getTemperature()
Return the motor controller temperature- Specified by:
getTemperaturein classWsMotorController- Returns:
- Current temperature.
-
sendDataToOutput
public void sendDataToOutput()
Sets motor speed to current value, from -1.0 to 1.0.- Specified by:
sendDataToOutputin classWsMotorController
-
notifyConfigChange
public void notifyConfigChange()
Does nothing, config values only affects start state.
-
-