How to set an Elevator's target Height?
Create and Configure our Elevator
Elevator// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot.subsystems;
import static edu.wpi.first.units.Units.Amps;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.MetersPerSecond;
import static edu.wpi.first.units.Units.MetersPerSecondPerSecond;
import static edu.wpi.first.units.Units.Feet;
import static edu.wpi.first.units.Units.Pounds;
import static edu.wpi.first.units.Units.Seconds;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import yams.mechanisms.SmartMechanism;
import yams.mechanisms.config.ElevatorConfig;
import yams.mechanisms.positional.Elevator;
import yams.motorcontrollers.SmartMotorController;
import yams.motorcontrollers.SmartMotorControllerConfig;
import yams.motorcontrollers.SmartMotorControllerConfig.ControlMode;
import yams.motorcontrollers.SmartMotorControllerConfig.MotorMode;
import yams.motorcontrollers.SmartMotorControllerConfig.TelemetryVerbosity;
import yams.motorcontrollers.local.SparkWrapper;
import yams.gearing.GearBox;
import yams.gearing.MechanismGearing;
public class ExampleSubsystem extends SubsystemBase {
private SmartMotorControllerConfig smcConfig = new SmartMotorControllerConfig(this)
.withControlMode(ControlMode.CLOSED_LOOP)
// Mechanism Circumference is the distance traveled by each mechanism rotation converting rotations to meters.
.withMechanismCircumference(Meters.of(Inches.of(0.25).in(Meters) * 22))
// Feedback Constants (PID Constants)
.withClosedLoopController(4, 0, 0, MetersPerSecond.of(0.5), MetersPerSecondPerSecond.of(0.5))
.withSimClosedLoopController(4, 0, 0, MetersPerSecond.of(0.5), MetersPerSecondPerSecond.of(0.5))
// Feedforward Constants
.withFeedforward(new ElevatorFeedforward(0, 0, 0))
.withSimFeedforward(new ElevatorFeedforward(0, 0, 0))
// Telemetry name and verbosity level
.withTelemetry("ElevatorMotor", TelemetryVerbosity.HIGH)
// Gearing from the motor rotor to final shaft.
// In this example gearbox(3,4) is the same as gearbox("3:1","4:1") which corresponds to the gearbox attached to your motor.
.withGearing(new MechanismGearing(GearBox.fromReductionStages(3, 4)))
// Motor properties to prevent over currenting.
.withMotorInverted(false)
.withIdleMode(MotorMode.BRAKE)
.withStatorCurrentLimit(Amps.of(40))
.withClosedLoopRampRate(Seconds.of(0.25))
.withOpenLoopRampRate(Seconds.of(0.25));
// Vendor motor controller object
private SparkMax spark = new SparkMax(4, MotorType.kBrushless);
// Create our SmartMotorController from our Spark and config with the NEO.
private SmartMotorController sparkSmartMotorController = new SparkWrapper(spark, DCMotor.getNEO(1), smcConfig);
private ElevatorConfig elevconfig = new ElevatorConfig(sparkSmartMotorController)
.withStartingHeight(Meters.of(0.5))
.withHardLimits(Meters.of(0), Meters.of(3))
.withTelemetry("Elevator", TelemetryVerbosity.HIGH)
.withMass(Pounds.of(16));
// Elevator Mechanism
private Elevator elevator = new Elevator(elevconfig);
/** Creates a new ExampleSubsystem. */
public ExampleSubsystem() {}
/**
* Example command factory method.
*
* @return a command
*/
public Command exampleMethodCommand() {
// Inline construction of command goes here.
// Subsystem::RunOnce implicitly requires `this` subsystem.
return runOnce(
() -> {
/* one-time action goes here */
});
}
/**
* An example method querying a boolean state of the subsystem (for example, a digital sensor).
*
* @return value of some boolean subsystem state, such as a digital sensor.
*/
public boolean exampleCondition() {
// Query some boolean state, such as a digital sensor.
return false;
}
@Override
public void periodic() {
// This method will be called once per scheduler run
elevator.updateTelemetry();
}
@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run during simulation
elevator.simIterate();
}
}Create Commands with our Elevator
Commands with our ElevatorBind buttons to our Elevator
ElevatorSimulate our Elevator!



Last updated