Skip to content

Commit

Permalink
basic code for shoulder.
Browse files Browse the repository at this point in the history
not yet integrated with OI or any Procedures.
  • Loading branch information
dejabot committed Nov 23, 2023
1 parent 9bffd1b commit a18d7b9
Show file tree
Hide file tree
Showing 5 changed files with 196 additions and 64 deletions.
11 changes: 11 additions & 0 deletions src/main/java/com/team766/robot/constants/ConfigConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,17 @@ private ConfigConstants() {}
public static final String ELEVATOR_MAX_VELOCITY = "elevator.sparkPID.maxVelocity";
public static final String ELEVATOR_MIN_OUTPUT_VELOCITY = "elevator.sparkPID.minOutputVelocity";
public static final String ELEVATOR_MAX_ACCEL = "elevator.sparkPID.maxAccel";

// shoulder config values
public static final String SHOULDER_LEFT_MOTOR = "shoulder.leftMotor";
public static final String SHOULDER_RIGHT_MOTOR = "shoulder.rightMotor";
public static final String SHOULDER_PGAIN = "shoulder.sparkPID.pGain";
public static final String SHOULDER_IGAIN = "shoulder.sparkPID.iGain";
public static final String SHOULDER_DGAIN = "shoulder.sparkPID.dGain";
public static final String SHOULDER_FFGAIN = "shoulder.sparkPID.ffGain";
public static final String SHOULDER_MAX_VELOCITY = "shoulder.sparkPID.maxVelocity";
public static final String SHOULDER_MIN_OUTPUT_VELOCITY = "shoulder.sparkPID.minOutputVelocity";
public static final String SHOULDER_MAX_ACCEL = "shoulder.sparkPID.maxAccel";
}


13 changes: 8 additions & 5 deletions src/main/java/com/team766/robot/mechanisms/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,16 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import static com.team766.robot.constants.ConfigConstants.*;

/**
* Basic elevator mechanism. Used in conjunction with the {@link Intake} and {@link Wrist}.
* Can be moved up and down as part of teleop or autonomous control to move the {@link Wrist}
* and {@link Intake} closer to a game piece or game element (eg node in the
* field, human player station).
*/
public class Elevator extends Mechanism {
public enum Position {

// TODO: do we need separate heights for cones vs cubes?

/** Elevator is fully retracted. */
/** Elevator is fully retracted. Starting position. */
RETRACTED(0),
/** Elevator is the appropriate height to place game pieces at the low node. */
LOW(5),
Expand Down Expand Up @@ -61,7 +65,6 @@ private double getHeight() {
private final ValueProvider<Double> minOutputVelocity;
private final ValueProvider<Double> maxAccel;


private final RateLimiter rateLimiter = new RateLimiter(1.0 /* seconds */);

/**
Expand All @@ -79,7 +82,7 @@ public Elevator() {
leftMotor = (CANSparkMax) halLeftMotor;
rightMotor = (CANSparkMax) halRightMotor;

rightMotor.follow(leftMotor, true);
rightMotor.follow(leftMotor, true /* invert */);

leftMotor.getEncoder().setPosition(EncoderUtils.elevatorHeightToRotations(Position.RETRACTED.getHeight()));

Expand Down
19 changes: 16 additions & 3 deletions src/main/java/com/team766/robot/mechanisms/EncoderUtils.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ private EncoderUtils() {
*/
public static double wristDegreesToRotations(double angle) {
// angle * net gear ratio * (rotations / degrees)
// FIXME: replace 32 with actual # of teeth
return angle * (72. / 10.) * (72. / 20.) * (48. / 24.) * (1. / 360.);
}

Expand All @@ -26,7 +25,6 @@ public static double wristDegreesToRotations(double angle) {
*/
public static double wristRotationsToDegrees(double rotations) {
// rotations * net gear ratio * (degrees / rotations)
// FIXME: replace 32 with actual # of teeth
return rotations * (10. / 72.) * (20. / 72.) * (24. / 48.) * (360. / 1.);
}

Expand All @@ -43,10 +41,25 @@ public static double elevatorHeightToRotations(double height) {
*/
public static double elevatorRotationsToHeight(double rotations) {
// rotations * net gear ratio * (height / rotations)
// FIXME: everything
return rotations * (12./36.) * ((1.641 * Math.PI)/1.);
}

/**
* Converts a target rotation (in degrees) to encoder units for the shoulder motor.
*/
public static double shoulderDegreesToRotations(double angle) {
// angle * net gear ratio * (rotations / degrees)
return angle * (4./1.) * (3. / 1.) * (1. / 360.);
}

/**
* Converts the shoulder motor's rotations to degrees.
*/
public static double shoulderRotationsToDegrees(double rotations) {
// rotations * net gear ratio * (degrees / rotations)
return rotations * (1. / 4.) * (1. / 3.) * (360. / 1.);
}

/**
* Cosine law
* @param side1
Expand Down
215 changes: 161 additions & 54 deletions src/main/java/com/team766/robot/mechanisms/Shoulder.java
Original file line number Diff line number Diff line change
@@ -1,83 +1,190 @@
package com.team766.robot.mechanisms;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.SparkMaxAbsoluteEncoder;
import com.revrobotics.SparkMaxAbsoluteEncoder.Type;
import com.revrobotics.SparkMaxPIDController;
import com.team766.config.ConfigFileReader;
import com.team766.framework.Mechanism;
import com.team766.hal.MotorController;
import com.team766.hal.RobotProvider;
import com.team766.library.RateLimiter;
import com.team766.library.ValueProvider;
import com.team766.logging.Severity;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import static com.team766.robot.constants.ConfigConstants.*;

/**
* Basic shoulder mechanism. Rotates the {@link Elevator} to different angles, to allow it (and the
* attached {@link Wrist} and {@link Intake}) to reach different positions, from the floor to different
* heights of nodes.
*/
public class Shoulder extends Mechanism {

/**
* Pre-set positions for the shoulder.
*/
public enum Position {

// TODO: adjust these!

/** Shoulder is in top position. */
TOP(45),

/** Shoulder is in position to intake and outtake pieces from/to the floor. Starting position. */
FLOOR(20),

/** Shoulder is fully down. **/
BOTTOM(15);

private final double angle;

Position(double angle) {
this.angle = angle;
}

private double getAngle() {
return angle;
}
}

public class Shoulder extends Mechanism{
private static final double NUDGE_INCREMENT = 5.0;
private static final double NUDGE_DAMPENER = 0.15;

private static final double NEAR_THRESHOLD = 5.0;

private double kF;
private double kP;
private double kI; // will most likley be 0
private double kD;
private final CANSparkMax leftMotor;
private final CANSparkMax rightMotor;
private final SparkMaxPIDController pidController;
private final ValueProvider<Double> pGain;
private final ValueProvider<Double> iGain;
private final ValueProvider<Double> dGain;
private final ValueProvider<Double> ffGain;
private final ValueProvider<Double> maxVelocity;
private final ValueProvider<Double> minOutputVelocity;
private final ValueProvider<Double> maxAccel;

private double setpoint;
private double allowedError;
private final RateLimiter rateLimiter = new RateLimiter(1.0 /* seconds */);

private double maxSpeed;
private double minSpeed;
private double maxAccel;
private double maxVel;
/**
* Constructs a new Shoulder.
*/
public Shoulder() {
MotorController halLeftMotor = RobotProvider.instance.getMotor(SHOULDER_LEFT_MOTOR);
MotorController halRightMotor = RobotProvider.instance.getMotor(SHOULDER_RIGHT_MOTOR);

public MotorController shoulderHallMotor = RobotProvider.instance.getMotor("shoulder"); // public for changing brake/coast mode without using a method
private CANSparkMax shoulderCanSparkMax = (CANSparkMax) shoulderHallMotor;
private SparkMaxPIDController shoulderPIDController = shoulderCanSparkMax.getPIDController();
if (!((halLeftMotor instanceof CANSparkMax)&&(halRightMotor instanceof CANSparkMax))) {
log(Severity.ERROR, "Motors are not CANSparkMaxes!");
throw new IllegalStateException("Motor are not CANSparkMaxes!");
}

public MotorController shoulderHallMotor2 = RobotProvider.instance.getMotor("shoulder2"); // public for changing brake/coast mode without using a method
private CANSparkMax shoulderCanSparkMax2 = (CANSparkMax) shoulderHallMotor2;
leftMotor = (CANSparkMax) halLeftMotor;
rightMotor = (CANSparkMax) halRightMotor;

rightMotor.follow(leftMotor, true /* invert */);

private static final double MAX_POSITION = 0; // figure it out
private static final double MIN_POSITION = 0; // figure it out
leftMotor.getEncoder().setPosition(EncoderUtils.elevatorHeightToRotations(Position.BOTTOM.getAngle()));

private static final double conePosition = 0; // figure it out
private static final double cubePosition = 0; // figure it out
private static final double restingPosition = 0; // figure it out
pidController = leftMotor.getPIDController();
pidController.setFeedbackDevice(leftMotor.getEncoder());

pGain = ConfigFileReader.getInstance().getDouble(SHOULDER_PGAIN);
iGain = ConfigFileReader.getInstance().getDouble(SHOULDER_IGAIN);
dGain = ConfigFileReader.getInstance().getDouble(SHOULDER_DGAIN);
ffGain = ConfigFileReader.getInstance().getDouble(SHOULDER_FFGAIN);
maxVelocity = ConfigFileReader.getInstance().getDouble(SHOULDER_MAX_VELOCITY);
minOutputVelocity = ConfigFileReader.getInstance().getDouble(SHOULDER_MIN_OUTPUT_VELOCITY);
maxAccel = ConfigFileReader.getInstance().getDouble(SHOULDER_MAX_ACCEL);
}

public Shoulder() {
kF = ConfigFileReader.getInstance().getDouble("shoulder.kF").get();
kP = ConfigFileReader.getInstance().getDouble("shoulder.kP").get();
kI = ConfigFileReader.getInstance().getDouble("shoulder.kI").get();
kD = ConfigFileReader.getInstance().getDouble("shoulder.kD").get();

allowedError = ConfigFileReader.getInstance().getDouble("shoulder.allowedError").get();

maxSpeed = ConfigFileReader.getInstance().getDouble("shoulder.maxSpeed").get();
minSpeed = ConfigFileReader.getInstance().getDouble("shoulder.minSpeed").get();
maxAccel = ConfigFileReader.getInstance().getDouble("shoulder.maxAccel").get();
maxVel = ConfigFileReader.getInstance().getDouble("shoulder.maxVel").get();

shoulderPIDController.setP(kP);
shoulderPIDController.setI(kI);
shoulderPIDController.setD(kD);
shoulderPIDController.setFF(kF);
shoulderPIDController.setOutputRange(minSpeed, maxSpeed);
shoulderPIDController.setSmartMotionMaxVelocity(maxVel, 0);
shoulderPIDController.setSmartMotionMaxAccel(maxAccel, 0);
shoulderPIDController.setSmartMotionMinOutputVelocity(0, 0);


shoulderPIDController.setSmartMotionAllowedClosedLoopError(allowedError, 0);
shoulderCanSparkMax1.getEncoder().setPosition(0); //reset to 0 at beginning.
shoulderCanSparkMax2.getEncoder().setPosition(0); //reset to 0 at beginning.
shoulderCanSparkMax2.follow(shoulderCanSparkMax1, true);
public double getRotations() {
return leftMotor.getEncoder().getPosition();
}

/**
* Returns the current angle of the wrist.
*/
public double getAngle() {
return EncoderUtils.shoulderRotationsToDegrees(leftMotor.getEncoder().getPosition());
}

public boolean isNearTo(Position position) {
return isNearTo(position.getAngle());
}

public boolean isNearTo(double angle) {
return Math.abs(angle - getAngle()) < NEAR_THRESHOLD;
}

public void nudgeNoPID(double value) {
checkContextOwnership();
double clampedValue = MathUtil.clamp(value, -1, 1);
clampedValue *= NUDGE_DAMPENER; // make nudges less forceful. TODO: make this non-linear
leftMotor.set(clampedValue);
}

public void stopShoulder() {
checkContextOwnership();
leftMotor.set(0);
}

public void nudgeUp() {
System.err.println("Nudging up.");
double angle = getAngle();
double targetAngle = Math.max(angle - NUDGE_INCREMENT, Position.TOP.getAngle());
System.err.println("Target: " + targetAngle);

rotate(targetAngle);
}

public void nudgeDown() {
System.err.println("Nudging down.");
double angle = getAngle();
double targetAngle = Math.min(angle + NUDGE_INCREMENT, Position.BOTTOM.getAngle());
rotate(targetAngle);
}

/**
* Rotates the wrist to a pre-set {@link Position}.
*/
public void rotate(Position position) {
rotate(position.getAngle());
}

public void setPosition(final double position){
setpoint = position;
/**
* Starts rotating the wrist to the specified angle.
* NOTE: this method returns immediately. Check the current wrist position of the wrist
* with {@link #getAngle()}.
*/
public void rotate(double angle) {
checkContextOwnership();

System.err.println("Setting target angle to " + angle);
// set the PID controller values with whatever the latest is in the config
pidController.setP(pGain.get());
pidController.setI(iGain.get());
pidController.setD(dGain.get());
// pidController.setFF(ffGain.get());
double ff = ffGain.get() * Math.cos(Math.toRadians(angle));
SmartDashboard.putNumber("[SHOULDER] ff", ff);
SmartDashboard.putNumber("[SHOULDER] reference", angle);

pidController.setOutputRange(-1, 1);

// convert the desired target degrees to rotations
double rotations = EncoderUtils.shoulderDegreesToRotations(angle);

// set the reference point for the wrist
pidController.setReference(rotations, ControlType.kPosition, 0, ff);
}

//should be called AOAP
public void run(){
shoulderPIDController.setReference(setpoint, com.revrobotics.ControlType.kPosition);
@Override
public void run() {
if (rateLimiter.next()) {
SmartDashboard.putNumber("[SHOULDER] Angle", getAngle());
SmartDashboard.putNumber("[SHOULDER] Rotations", getRotations());
}
}

}
2 changes: 0 additions & 2 deletions src/main/java/com/team766/robot/mechanisms/Wrist.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@ public class Wrist extends Mechanism {
*/
public enum Position {

// TODO: adjust these values.

/** Wrist is in top position. Starting position. */
TOP(-135),
/** Wrist is in the position for moving around the field. */
Expand Down

0 comments on commit a18d7b9

Please sign in to comment.