Package edu.wpi.first.wpilibj.simulation
Class ElevatorSim
java.lang.Object
edu.wpi.first.wpilibj.simulation.LinearSystemSim<N2,N1,N2>
edu.wpi.first.wpilibj.simulation.ElevatorSim
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
ConstructorsConstructorDescriptionElevatorSim
(double kV, double kA, DCMotor gearbox, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... measurementStdDevs) Creates a simulated elevator mechanism.ElevatorSim
(LinearSystem<N2, N1, N2> plant, DCMotor gearbox, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... measurementStdDevs) Creates a simulated elevator mechanism.ElevatorSim
(DCMotor gearbox, double gearing, double carriageMass, double drumRadius, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... measurementStdDevs) Creates a simulated elevator mechanism. -
Method Summary
Modifier and TypeMethodDescriptiondouble
Returns the elevator current draw.double
Returns the position of the elevator.double
Returns the velocity of the elevator.boolean
Returns whether the elevator has hit the lower limit.boolean
Returns whether the elevator has hit the upper limit.void
setInputVoltage
(double volts) Sets the input voltage for the elevator.final void
setState
(double position, double velocity) Sets the elevator's state.Updates the state of the elevator.boolean
wouldHitLowerLimit
(double elevatorHeight) Returns whether the elevator would hit the lower limit.boolean
wouldHitUpperLimit
(double elevatorHeight) Returns whether the elevator would hit the upper limit.
-
Constructor Details
-
ElevatorSim
public ElevatorSim(LinearSystem<N2, N1, N2> plant, DCMotor gearbox, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... measurementStdDevs) Creates a simulated elevator mechanism.- Parameters:
plant
- The linear system that represents the elevator. This system can be created withLinearSystemId.createElevatorSystem(DCMotor, double, double, double)
.gearbox
- The type of and number of motors in the elevator gearbox.minHeight
- The min allowable height of the elevator in meters.maxHeight
- The max allowable height of the elevator in meters.simulateGravity
- Whether gravity should be simulated or not.startingHeight
- The starting height of the elevator in meters.measurementStdDevs
- The standard deviations of the measurements. Can be omitted if no noise is desired. If present must have 1 element for position.
-
ElevatorSim
public ElevatorSim(double kV, double kA, DCMotor gearbox, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... measurementStdDevs) Creates a simulated elevator mechanism.- Parameters:
kV
- The velocity gain.kA
- The acceleration gain.gearbox
- The type of and number of motors in the elevator gearbox.minHeight
- The min allowable height of the elevator in meters.maxHeight
- The max allowable height of the elevator in meters.simulateGravity
- Whether gravity should be simulated or not.startingHeight
- The starting height of the elevator in meters.measurementStdDevs
- The standard deviations of the measurements. Can be omitted if no noise is desired. If present must have 1 element for position.
-
ElevatorSim
public ElevatorSim(DCMotor gearbox, double gearing, double carriageMass, double drumRadius, double minHeight, double maxHeight, boolean simulateGravity, double startingHeight, double... 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).carriageMass
- The mass of the elevator carriage in kg.drumRadius
- The radius of the drum that the elevator spool is wrapped around in meters.minHeight
- The min allowable height of the elevator in meters.maxHeight
- The max allowable height of the elevator in meters.simulateGravity
- Whether gravity should be simulated or not.startingHeight
- The starting height of the elevator in meters.measurementStdDevs
- The standard deviations of the measurements. Can be omitted if no noise is desired. If present must have 1 element for position.
-
-
Method Details
-
setState
Sets the elevator's state. The new position will be limited between the minimum and maximum allowed heights.- Parameters:
position
- The new position in meters.velocity
- New velocity in meters per second.
-
wouldHitLowerLimit
Returns whether the elevator would hit the lower limit.- Parameters:
elevatorHeight
- The elevator height in meters.- Returns:
- Whether the elevator would hit the lower limit.
-
wouldHitUpperLimit
Returns whether the elevator would hit the upper limit.- Parameters:
elevatorHeight
- The elevator height in meters.- 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.
-
getPosition
Returns the position of the elevator.- Returns:
- The position of the elevator in meters.
-
getVelocity
Returns the velocity of the elevator.- Returns:
- The velocity of the elevator in meters per second.
-
getCurrentDraw
Returns the elevator current draw.- Returns:
- The elevator current draw in amps.
-
setInputVoltage
Sets the input voltage for the elevator.- Parameters:
volts
- The input voltage.
-
updateX
Updates the state of the elevator.- Overrides:
updateX
in classLinearSystemSim<N2,
N1, N2> - Parameters:
currentXhat
- The current state estimate.u
- The system inputs (voltage).dt
- The time difference between controller updates in seconds.- Returns:
- The new state.
-