Package edu.wpi.first.wpilibj.simulation
Class DCMotorSim
java.lang.Object
edu.wpi.first.wpilibj.simulation.LinearSystemSim<N2,N1,N2>
edu.wpi.first.wpilibj.simulation.DCMotorSim
Represents a simulated DC motor 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
ConstructorsConstructorDescriptionDCMotorSim
(LinearSystem<N2, N1, N2> plant, DCMotor gearbox, double... measurementStdDevs) Creates a simulated DC motor mechanism. -
Method Summary
Modifier and TypeMethodDescriptiondouble
Returns the DC motor's acceleration.double
Returns the DC motor's position.double
Returns the DC motor's velocity.double
Returns the DC motor's current draw.Returns the gearbox for the DC motor.double
Returns the gear ratio of the DC motor.double
Gets the input voltage for the DC motor.double
getJ()
Returns the moment of inertia of the DC motor.double
Returns the DC motor's torque in.void
setAngle
(double angularPosition) Sets the DC motor's angular position.void
setAngularVelocity
(double angularVelocity) Sets the DC motor's angular velocity.void
setInputVoltage
(double volts) Sets the input voltage for the DC motor.void
setState
(double angularPosition, double angularVelocity) Sets the state of the DC motor.
-
Constructor Details
-
DCMotorSim
Creates a simulated DC motor mechanism.- Parameters:
plant
- The linear system representing the DC motor. This system can be created withLinearSystemId.createDCMotorSystem(DCMotor, double, double)
orLinearSystemId.createDCMotorSystem(double, double)
. IfLinearSystemId.createDCMotorSystem(double, double)
is used, the distance unit must be radians.gearbox
- The type of and number of motors in the DC motor gearbox.measurementStdDevs
- The standard deviations of the measurements. Can be omitted if no noise is desired. If present must have 2 elements. The first element is for position. The second element is for velocity.
-
-
Method Details
-
setState
Sets the state of the DC motor.- Parameters:
angularPosition
- The new position in radians.angularVelocity
- The new velocity in radians per second.
-
setAngle
Sets the DC motor's angular position.- Parameters:
angularPosition
- The new position in radians.
-
setAngularVelocity
Sets the DC motor's angular velocity.- Parameters:
angularVelocity
- The new velocity in radians per second.
-
getGearing
Returns the gear ratio of the DC motor.- Returns:
- the DC motor's gear ratio.
-
getJ
Returns the moment of inertia of the DC motor.- Returns:
- The DC motor's moment of inertia in kg-m².
-
getGearbox
Returns the gearbox for the DC motor.- Returns:
- The DC motor's gearbox.
-
getAngularPosition
Returns the DC motor's position.- Returns:
- The DC motor's position in radians.
-
getAngularVelocity
Returns the DC motor's velocity.- Returns:
- The DC motor's velocity in radians per second.
-
getAngularAcceleration
Returns the DC motor's acceleration.- Returns:
- The DC motor's acceleration in rad/s².
-
getTorque
Returns the DC motor's torque in.- Returns:
- The DC motor's torque in Newton-meters.
-
getCurrentDraw
Returns the DC motor's current draw.- Returns:
- The DC motor's current draw in amps.
-
getInputVoltage
Gets the input voltage for the DC motor.- Returns:
- The DC motor's input voltage.
-
setInputVoltage
Sets the input voltage for the DC motor.- Parameters:
volts
- The input voltage.
-