Package tagalong.subsystems.micro
Class Roller
java.lang.Object
tagalong.subsystems.micro.Microsystem
tagalong.subsystems.micro.Roller
Roller microsystem
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected doubleSimulated current angle of the rollerfinal doubleDefault lower tolerance for roller in rotationsfinal doubleDefault upper tolerance for roller in rotationsfinal doubleMaximum acceleration in rotations per second squaredfinal doubleMaximum velocity in rotations per secondfinal RollerConfConfiguration for the rollerprotected SimpleMotorFeedforwardFeedforward model of the rollerprotected FlywheelSimFlywheel simulation for the roller motorprotected doubleSimulated acceleration in rotations per minute squaredprotected doubleSimulated number of rotationsprotected doubleSimulated velocity in rotations per minuteFields inherited from class tagalong.subsystems.micro.Microsystem
_allMotors, _conf, _configuredMicrosystemDisable, _currentPositionEntry, _currentVelocityEntry, _curState, _followProfile, _goalState, _isFFTuningMicro, _isMicrosystemDisabled, _isPIDTuningMicro, _isShuffleboardMicro, _KAEntry, _KGEntry, _KSEntry, _KVEntry, _mechanism, _primaryMotor, _primaryMotorSim, _profileTimer, _requestedPositionVoltage, _requestedTorqueCurrent, _requestedVelocityVoltage, _root, _slot0DFactorEntry, _slot0IFactorEntry, _slot0PFactorEntry, _slot1DFactorEntry, _slot1IFactorEntry, _slot1PFactorEntry, _slot2DFactorEntry, _slot2IFactorEntry, _slot2PFactorEntry, _targetPositionEntry, _targetVelocityEntry, _toleranceTimer, _trapProfile, _tuningTabCounter -
Constructor Summary
ConstructorsConstructorDescriptionRoller(RollerConf conf) Constructs a roller microsystem with the below configurations -
Method Summary
Modifier and TypeMethodDescriptionvoidConfigures a user interface on the Shuffleboard for the specified micro systemvoidCalculates the next state according to the trapezoidal profile and requests the roller motor(s) to arrive at the next position with feedforwardRetrieves ligaments attached to roller Mechanism2ddoubleGets the position of the roller in rotationsdoubleGets the power of the primary roller motordoubleGets the velocity of roller in rotationsvoidSets the power of the primary motor to zerobooleanisRollerAtTargetSpeed(double targetSpeed) Checks if the roller is at the target speedbooleanisRollerInTolerance(double lowerBound, double upperBound) Bounds checking function that uses the current roller positionbooleandoublemotorToRollerRot(double motorRot) Converts motor rotations to roller rotationsvoidreturns nothing if micro system is disabledvoidonEnable()Sets break mode for all motors If system is in PID tuning mode is updates all PID related settings If the system is in Feedforward Tuning mode, it sets the primary motor to coast mode.voidperiodic()Periodic update functiondoublerollerRotToMotor(double rollerRot) Converts motor rotations to roller rotationsvoidsetRollerPower(double power) Sets the power of the primary roller motorsetRollerPowerCmd(double power) Command that sets the roller powervoidsetRollerProfile(double goalPositionRot) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(double goalPositionRot, double goalVelocityRPS) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(Angle goalPosition) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(Angle goalPosition, double goalVelocityRPS) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2) Creates a new trapezoidal profile for the roller to followvoidsetRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState) Creates a new trapezoidal profile for the roller to followsetRollerRPSCmd(double rps) Command that sets the velocity of the roller in rotations per secondsetRollerRPSWithFFCmd(double rps) Command that sets the velocity of the roller in rotations per second with feedforwardvoidsetRollerVelocity(double rps, boolean withFF) Sets the velocity of the roller in RPSvoidInitializes simulationvoidPeriodic function during simulationstartEndRollerPowerCmd(double power) Command that sets the power of the primary motor (zero if interrupted)startEndRollerRPSCmd(double rps) Command that sets the velocity of the roller in rotations per second (sets zero power if interrupted)startEndRollerRPSWithFFCmd(double rps) Command that sets the velocity of the roller in rotations per second with feedforward.voidUpdates shuffleboardMethods inherited from class tagalong.subsystems.micro.Microsystem
checkInitStatus, checkToleranceTime, configAllDevices, configTuningModes, disableMicrosystem, getPrimaryMotor, getPrimaryMotorPosition, getPrimaryMotorPower, getPrimaryMotorVelocity, getRoot, isProfileFinished, onTeleopDisable, resetToleranceTimer, setBrakeMode, setFollowProfile, setHoldPosition, setPrimaryPower, updateAllPIDSGVA, waitForInitialization
-
Field Details
-
_rollerConf
Configuration for the roller -
_defaultRollerLowerToleranceRot
Default lower tolerance for roller in rotations -
_defaultRollerUpperToleranceRot
Default upper tolerance for roller in rotations -
_maxVelocityRPS
Maximum velocity in rotations per second -
_maxAccelerationRPS2
Maximum acceleration in rotations per second squared -
_rollerFF
Feedforward model of the roller -
_rollerSim
Flywheel simulation for the roller motor -
_simRotations
Simulated number of rotations -
_simVeloRPM
Simulated velocity in rotations per minute -
_simAccelRPM2
Simulated acceleration in rotations per minute squared -
_curSimAngle
Simulated current angle of the roller
-
-
Constructor Details
-
Roller
Constructs a roller microsystem with the below configurations- Parameters:
conf- Configuration for the roller
-
-
Method Details
-
onEnable
Description copied from class:MicrosystemSets break mode for all motors If system is in PID tuning mode is updates all PID related settings If the system is in Feedforward Tuning mode, it sets the primary motor to coast mode.- Overrides:
onEnablein classMicrosystem
-
onDisable
Description copied from class:Microsystemreturns nothing if micro system is disabled- Overrides:
onDisablein classMicrosystem
-
periodic
Periodic update function- Overrides:
periodicin classMicrosystem
-
simulationInit
Description copied from class:MicrosystemInitializes simulation- Overrides:
simulationInitin classMicrosystem
-
simulationPeriodic
Description copied from class:MicrosystemPeriodic function during simulation- Overrides:
simulationPeriodicin classMicrosystem
-
motorResetConfig
- Overrides:
motorResetConfigin classMicrosystem- Returns:
- boolean (micro system is enabled and the primary motor has been reset and if successful, it reconfigures the devices and returns true)
-
updateShuffleboard
Description copied from class:MicrosystemUpdates shuffleboard- Overrides:
updateShuffleboardin classMicrosystem
-
configShuffleboard
Description copied from class:MicrosystemConfigures a user interface on the Shuffleboard for the specified micro system- Overrides:
configShuffleboardin classMicrosystem
-
motorToRollerRot
Converts motor rotations to roller rotations- Parameters:
motorRot- motor rotations- Returns:
- roller rotations converted from motor rotations
-
rollerRotToMotor
Converts motor rotations to roller rotations- Parameters:
rollerRot- roller rotations- Returns:
- motor rotations converted from roller rotations
-
followLastProfile
Calculates the next state according to the trapezoidal profile and requests the roller motor(s) to arrive at the next position with feedforward -
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPosition- goal position in rotations
-
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPosition- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per second
-
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPosition- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per second
-
setRollerProfile
public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2) Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPosition- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per secondmaxAccelerationRPS2- maximum acceleration in rotations per second squared
-
setRollerProfile
public void setRollerProfile(Angle goalPosition, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState) Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPosition- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per secondmaxAccelerationRPS2- maximum acceleration in rotations per second squaredsetCurrentState- True if the profiles current state should base itself off sensor values rather than continue from the existing state
-
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPositionRot- goal position in rotations
-
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPositionRot- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per second
-
setRollerProfile
Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPositionRot- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per second
-
setRollerProfile
public void setRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2) Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPositionRot- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per secondmaxAccelerationRPS2- maximum acceleration in rotations per second squared
-
setRollerProfile
public void setRollerProfile(double goalPositionRot, double goalVelocityRPS, double maxVelocityRPS, double maxAccelerationRPS2, boolean setCurrentState) Creates a new trapezoidal profile for the roller to follow- Parameters:
goalPositionRot- goal position in rotationsgoalVelocityRPS- goal velocity in rotations per secondmaxVelocityRPS- maximum velocity in rotations per secondmaxAccelerationRPS2- maximum acceleration in rotations per second squaredsetCurrentState- True if the profiles current state should base itself off sensor values rather than continue from the existing state
-
setRollerPower
Sets the power of the primary roller motor- Parameters:
power- roller power
-
getRollerPower
Gets the power of the primary roller motor- Returns:
- roller power
-
getRollerPosition
Gets the position of the roller in rotations- Returns:
- roller position in rotations
-
getRollerVelocity
Gets the velocity of roller in rotations- Returns:
- roller velocity
-
setRollerVelocity
Sets the velocity of the roller in RPS- Parameters:
rps- Desired velocity in rotations per secondwithFF- with feedforward
-
isRollerAtTargetSpeed
Checks if the roller is at the target speed- Parameters:
targetSpeed- target speed in rotations per second- Returns:
- if roller is at target speed
-
setRollerPowerCmd
Command that sets the roller power- Parameters:
power- roller power- Returns:
- instant command to set roller power
-
setRollerRPSCmd
Command that sets the velocity of the roller in rotations per second- Parameters:
rps- rotations per second- Returns:
- instant command to set roller velocity
-
setRollerRPSWithFFCmd
Command that sets the velocity of the roller in rotations per second with feedforward- Parameters:
rps- rotations per second- Returns:
- instant command to set roller velocity with feedforward
-
startEndRollerPowerCmd
Command that sets the power of the primary motor (zero if interrupted)- Parameters:
power- roller power- Returns:
- start end command to set roller power
-
startEndRollerRPSCmd
Command that sets the velocity of the roller in rotations per second (sets zero power if interrupted)- Parameters:
rps- rotations per second- Returns:
- start end command to set roller velocity
-
startEndRollerRPSWithFFCmd
Command that sets the velocity of the roller in rotations per second with feedforward. (sets zero power if interrupted)- Parameters:
rps- rotations per second- Returns:
- start end command to set roller velocity with feedforward
-
isRollerInTolerance
Bounds checking function that uses the current roller position- Parameters:
lowerBound- minimum of acceptable rangeupperBound- maximum of acceptable range- Returns:
- if the current position is in specified acceptable range
-
holdCurrentPosition
Description copied from class:MicrosystemSets the power of the primary motor to zero- Overrides:
holdCurrentPositionin classMicrosystem
-
getRollerLigaments
Retrieves ligaments attached to roller Mechanism2d- Returns:
- roller ligaments
-