Class SwerveSteeringSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
xbot.common.command.BaseSubsystem
xbot.common.command.BaseSetpointSubsystem<Double,Double>
xbot.common.command.BaseSimpleSetpointSubsystem
xbot.common.subsystems.drive.swerve.SwerveSteeringSubsystem
- All Implemented Interfaces:
Sendable,Subsystem,DataFrameRefreshable,SupportsSetpointLock,IPropertySupport
-
Field Summary
Fields inherited from class xbot.common.command.BaseSetpointSubsystem
atGoal, lastTargetValueUsedforAtGoalFields inherited from class xbot.common.command.BaseSubsystem
aKitLog, dataFrameRefreshables -
Constructor Summary
ConstructorsConstructorDescriptionSwerveSteeringSubsystem(SwerveInstance swerveInstance, XCANMotorController.XCANMotorControllerFactory mcFactory, XCANCoder.XCANCoderFactory canCoderFactory, PropertyFactory pf, PIDManager.PIDManagerFactory pidf, XSwerveDriveElectricalContract electricalContract) -
Method Summary
Modifier and TypeMethodDescriptionGets the reported position of the CANCoder.Gets the current position of the mechanism using the best available encoder.Gets current angle as a Rotation2dGets current angle in degreesGets the CANCoder for this steering module.getLabel()Gets the motor controller for this steering module.Gets target angle in degreesbooleanvoidperiodic()This method is called on eachCommandSchedulerloop.voidConsumes and processes inputs from the device or subsystem.voidCalculates the nearest position on the motor encoder to targetDegrees and sets the controller's PID target.voidSets the output power of the motor.voidsetTargetValue(Double value) Sets target angle in degreessysIdDynamic(SysIdRoutine.Direction direction) Gets a command to run the SysId routine in the dynamic mode.sysIdQuasistatic(SysIdRoutine.Direction direction) Gets a command to run the SysId routine in the quasistatic mode.Methods inherited from class xbot.common.command.BaseSimpleSetpointSubsystem
areTwoTargetsEquivalentMethods inherited from class xbot.common.command.BaseSetpointSubsystem
areTwoDoublesEquivalent, areTwoDoublesEquivalent, createSetTargetCommand, createSetTargetCommand, getSetpointLock, isMaintainerAtGoal, setMaintainerIsAtGoalMethods inherited from class xbot.common.command.BaseSubsystem
registerDataFrameRefreshableMethods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystemMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
-
Constructor Details
-
SwerveSteeringSubsystem
@Inject public SwerveSteeringSubsystem(SwerveInstance swerveInstance, XCANMotorController.XCANMotorControllerFactory mcFactory, XCANCoder.XCANCoderFactory canCoderFactory, PropertyFactory pf, PIDManager.PIDManagerFactory pidf, XSwerveDriveElectricalContract electricalContract)
-
-
Method Details
-
getLabel
-
getPrefix
- Specified by:
getPrefixin interfaceIPropertySupport- Overrides:
getPrefixin classBaseSubsystem
-
getCurrentValue
Gets current angle in degrees- Specified by:
getCurrentValuein classBaseSetpointSubsystem<Double,Double>
-
getCurrentRotation
Gets current angle as a Rotation2d -
getTargetValue
Gets target angle in degrees- Specified by:
getTargetValuein classBaseSetpointSubsystem<Double,Double>
-
setTargetValue
Sets target angle in degrees- Specified by:
setTargetValuein classBaseSetpointSubsystem<Double,Double>
-
setPower
Sets the output power of the motor.- Specified by:
setPowerin classBaseSetpointSubsystem<Double,Double> - Parameters:
power- The power value, between -1 and 1.
-
isCalibrated
public boolean isCalibrated()- Specified by:
isCalibratedin classBaseSetpointSubsystem<Double,Double>
-
sysIdQuasistatic
Gets a command to run the SysId routine in the quasistatic mode.- Parameters:
direction- The direction to run the SysId routine.- Returns:
- The command to run the SysId routine.
-
sysIdDynamic
Gets a command to run the SysId routine in the dynamic mode.- Parameters:
direction- The direction to run the SysId routine.- Returns:
- The command to run the SysId routine.
-
getVelocity
-
getMotorController
Gets the motor controller for this steering module.- Returns:
- The motor controller for this steering module.
-
getEncoder
Gets the CANCoder for this steering module.- Returns:
- The CANCoder for this steering module.
-
getBestEncoderPosition
Gets the current position of the mechanism using the best available encoder.- Returns:
- The position in degrees.
-
getAbsoluteEncoderPosition
Gets the reported position of the CANCoder.- Returns:
- The position of the CANCoder.
-
setMotorControllerPidTarget
public void setMotorControllerPidTarget()Calculates the nearest position on the motor encoder to targetDegrees and sets the controller's PID target. -
periodic
public void periodic()Description copied from class:BaseSubsystemThis method is called on eachCommandSchedulerloop.- Specified by:
periodicin interfaceSubsystem- Overrides:
periodicin classBaseSubsystem
-
refreshDataFrame
public void refreshDataFrame()Description copied from interface:DataFrameRefreshableConsumes and processes inputs from the device or subsystem.- Specified by:
refreshDataFramein interfaceDataFrameRefreshable- Overrides:
refreshDataFramein classBaseSubsystem
-