Class SwerveModuleSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
xbot.common.command.BaseSubsystem
xbot.common.subsystems.drive.swerve.SwerveModuleSubsystem
- All Implemented Interfaces:
Sendable,Subsystem,DataFrameRefreshable,IPropertySupport
-
Field Summary
Fields inherited from class xbot.common.command.BaseSubsystem
aKitLog, dataFrameRefreshables -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModuleSubsystem(SwerveInstance swerveInstance, SwerveDriveSubsystem driveSubsystem, SwerveSteeringSubsystem steeringSubsystem, XSwerveDriveElectricalContract contract, PropertyFactory pf) -
Method Summary
Modifier and TypeMethodDescriptionGets the current state of the module, in METRIC UNITS.voidperiodic()This method is called on eachCommandSchedulerloop.voidConsumes and processes inputs from the device or subsystem.voidvoidsetNoviceMode(boolean enabled) voidsetPowers(double drivePower, double steeringPower) Very basic drive method - bypasses all PID to directly control the motors.voidsetTargetState(SwerveModuleState swerveModuleState) Sets the target steering angle and drive power for this module, in METRIC UNITS.voidsetTargetState(SwerveModuleState swerveModuleState, boolean optimize) Methods 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
-
SwerveModuleSubsystem
@Inject public SwerveModuleSubsystem(SwerveInstance swerveInstance, SwerveDriveSubsystem driveSubsystem, SwerveSteeringSubsystem steeringSubsystem, XSwerveDriveElectricalContract contract, PropertyFactory pf)
-
-
Method Details
-
setTargetState
Sets the target steering angle and drive power for this module, in METRIC UNITS.- Parameters:
swerveModuleState- Metric swerve module state
-
setTargetState
-
getCurrentState
Gets the current state of the module, in METRIC UNITS.- Returns:
- Metric swerve module state
-
getCurrentPosition
-
getTargetState
-
getPrefix
- Specified by:
getPrefixin interfaceIPropertySupport- Overrides:
getPrefixin classBaseSubsystem
-
getModuleTranslation
-
getDriveSubsystem
-
getSteeringSubsystem
-
setNoviceMode
public void setNoviceMode(boolean enabled) -
setPowers
public void setPowers(double drivePower, double steeringPower) Very basic drive method - bypasses all PID to directly control the motors. Ensure that your command has required control of all relevant subsystems before doing this, or you will be fighting the maintainers.- Parameters:
drivePower- -1 to 1 value for nodule wheel powersteeringPower- -1 to 1 value for module rotation power
-
setDriveCurrentLimits
-
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
-