Package edu.wpi.first.wpilibj.simulation
Class ElevatorSim
java.lang.Object
edu.wpi.first.wpilibj.simulation.LinearSystemSim<N2,N1,N1>
edu.wpi.first.wpilibj.simulation.ElevatorSim
public class ElevatorSim extends LinearSystemSim<N2,N1,N1>
Represents a simulated elevator mechanism.
-
Field Summary
Fields inherited from class edu.wpi.first.wpilibj.simulation.LinearSystemSim
m_measurementStdDevs, m_plant, m_u, m_x, m_y -
Constructor Summary
Constructors Constructor Description ElevatorSim(LinearSystem<N2,N1,N1> plant, DCMotor gearbox, double gearing, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters)Creates a simulated elevator mechanism.ElevatorSim(LinearSystem<N2,N1,N1> plant, DCMotor gearbox, double gearing, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters, Matrix<N1,N1> measurementStdDevs)Creates a simulated elevator mechanism.ElevatorSim(DCMotor gearbox, double gearing, double carriageMassKg, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters)Creates a simulated elevator mechanism.ElevatorSim(DCMotor gearbox, double gearing, double carriageMassKg, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters, Matrix<N1,N1> measurementStdDevs)Creates a simulated elevator mechanism. -
Method Summary
Modifier and Type Method Description doublegetCurrentDrawAmps()Returns the elevator current draw.doublegetPositionMeters()Returns the position of the elevator.doublegetVelocityMetersPerSecond()Returns the velocity of the elevator.booleanhasHitLowerLimit()Returns whether the elevator has hit the lower limit.booleanhasHitUpperLimit()Returns whether the elevator has hit the upper limit.voidsetInputVoltage(double volts)Sets the input voltage for the elevator.protected Matrix<N2,N1>updateX(Matrix<N2,N1> currentXhat, Matrix<N1,N1> u, double dtSeconds)Updates the state of the elevator.booleanwouldHitLowerLimit(double elevatorHeightMeters)Returns whether the elevator would hit the lower limit.booleanwouldHitUpperLimit(double elevatorHeightMeters)Returns whether the elevator would hit the upper limit.Methods inherited from class edu.wpi.first.wpilibj.simulation.LinearSystemSim
clampInput, getOutput, getOutput, setInput, setInput, setInput, setState, update
-
Constructor Details
-
ElevatorSim
public ElevatorSim(LinearSystem<N2,N1,N1> plant, DCMotor gearbox, double gearing, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters)Creates a simulated elevator mechanism.- Parameters:
plant- The linear system that represents the elevator.gearbox- The type of and number of motors in the elevator gearbox.gearing- The gearing of the elevator (numbers greater than 1 represent reductions).drumRadiusMeters- The radius of the drum that the elevator spool is wrapped around.minHeightMeters- The min allowable height of the elevator.maxHeightMeters- The max allowable height of the elevator.
-
ElevatorSim
public ElevatorSim(LinearSystem<N2,N1,N1> plant, DCMotor gearbox, double gearing, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters, Matrix<N1,N1> measurementStdDevs)Creates a simulated elevator mechanism.- Parameters:
plant- The linear system that represents the elevator.gearbox- The type of and number of motors in the elevator gearbox.gearing- The gearing of the elevator (numbers greater than 1 represent reductions).drumRadiusMeters- The radius of the drum that the elevator spool is wrapped around.minHeightMeters- The min allowable height of the elevator.maxHeightMeters- The max allowable height of the elevator.measurementStdDevs- The standard deviations of the measurements.
-
ElevatorSim
public ElevatorSim(DCMotor gearbox, double gearing, double carriageMassKg, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters)Creates a simulated elevator mechanism.- Parameters:
gearbox- The type of and number of motors in the elevator gearbox.gearing- The gearing of the elevator (numbers greater than 1 represent reductions).carriageMassKg- The mass of the elevator carriage.drumRadiusMeters- The radius of the drum that the elevator spool is wrapped around.minHeightMeters- The min allowable height of the elevator.maxHeightMeters- The max allowable height of the elevator.
-
ElevatorSim
public ElevatorSim(DCMotor gearbox, double gearing, double carriageMassKg, double drumRadiusMeters, double minHeightMeters, double maxHeightMeters, Matrix<N1,N1> measurementStdDevs)Creates a simulated elevator mechanism.- Parameters:
gearbox- The type of and number of motors in the elevator gearbox.gearing- The gearing of the elevator (numbers greater than 1 represent reductions).carriageMassKg- The mass of the elevator carriage.drumRadiusMeters- The radius of the drum that the elevator spool is wrapped around.minHeightMeters- The min allowable height of the elevator.maxHeightMeters- The max allowable height of the elevator.measurementStdDevs- The standard deviations of the measurements.
-
-
Method Details
-
wouldHitLowerLimit
Returns whether the elevator would hit the lower limit.- Parameters:
elevatorHeightMeters- The elevator height.- Returns:
- Whether the elevator would hit the lower limit.
-
wouldHitUpperLimit
Returns whether the elevator would hit the upper limit.- Parameters:
elevatorHeightMeters- The elevator height.- Returns:
- Whether the elevator would hit the upper limit.
-
hasHitLowerLimit
Returns whether the elevator has hit the lower limit.- Returns:
- Whether the elevator has hit the lower limit.
-
hasHitUpperLimit
Returns whether the elevator has hit the upper limit.- Returns:
- Whether the elevator has hit the upper limit.
-
getPositionMeters
Returns the position of the elevator.- Returns:
- The position of the elevator.
-
getVelocityMetersPerSecond
Returns the velocity of the elevator.- Returns:
- The velocity of the elevator.
-
getCurrentDrawAmps
Returns the elevator current draw.- Overrides:
getCurrentDrawAmpsin classLinearSystemSim<N2,N1,N1>- Returns:
- The elevator current draw.
-
setInputVoltage
Sets the input voltage for the elevator.- Parameters:
volts- The input voltage.
-
updateX
Updates the state of the elevator.- Overrides:
updateXin classLinearSystemSim<N2,N1,N1>- Parameters:
currentXhat- The current state estimate.u- The system inputs (voltage).dtSeconds- The time difference between controller updates.- Returns:
- The new state.
-