Skip to content
Open
Show file tree
Hide file tree
Changes from 10 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions src/main/java/org/techvalleyhigh/frc5881/deepspace/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.climber.ClimberLegsBackToggle;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.climber.ClimberLegsFrontToggle;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.ElevatorDown;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.ElevatorUp;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.LiftDown;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.LiftUp;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.groups.SwitchRobotMode;

/**
Expand Down Expand Up @@ -86,9 +86,9 @@ Right thumb stick drives climber (up and down)
// When the "Y" button is pressed change the arm mode
driveControllerButtonY.whenPressed(new SwitchRobotMode());

// When the left/ right bumper is pressed lower or raise the elevator
driveControllerLeftBumper.whenPressed(new ElevatorDown());
driveControllerRightBumper.whenPressed(new ElevatorUp());
// When the left/ right bumper is pressed lower or raise the lift
driveControllerLeftBumper.whenPressed(new LiftDown());
driveControllerRightBumper.whenPressed(new LiftUp());

// When the "Back" button is pressed toggle front climber
driveControllerBackButton.whenPressed(new ClimberLegsFrontToggle());
Expand Down
125 changes: 115 additions & 10 deletions src/main/java/org/techvalleyhigh/frc5881/deepspace/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,10 @@
import com.kauailabs.navx.frc.AHRS;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.ElevatorSave;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.elevator.LiftSave;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.drive.ArcadeDrive;
import org.techvalleyhigh.frc5881.deepspace.robot.commands.drive.DriveSave;
import org.techvalleyhigh.frc5881.deepspace.robot.subsystem.*;
Expand All @@ -20,6 +21,10 @@
public class Robot extends TimedRobot {
private static final String kDefaultAuto = "Default";
private static final String kCustomAuto = "My Auto";

private int ticks = 0;
private long lastTime = System.currentTimeMillis();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These need comments as to what they are for....

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This can be removed


private String m_autoSelected;
private final SendableChooser<String> m_chooser = new SendableChooser<>();

Expand All @@ -30,7 +35,6 @@ public class Robot extends TimedRobot {
public static DriveControl driveControl;
public static Elevator elevator;
public static Intake intake;
public static Arm arm;
public static UpsideDown upsideDown;
public static LED led;

Expand All @@ -52,7 +56,6 @@ public void robotInit() {
elevator = new Elevator();
intake = new Intake();
upsideDown = new UpsideDown();
arm = new Arm();

/*
OI must be constructed after subsystems. If the OI creates Commands
Expand All @@ -64,8 +67,13 @@ constructed yet. Thus, their requires() statements may grab null

driveCommand = new ArcadeDrive();

SPI.Port port = SPI.Port.kOnboardCS0;
navX = new AHRS(port);
try {
SPI.Port port = SPI.Port.kMXP;
navX = new AHRS(port);
} catch (RuntimeException ex) {
System.err.println(ex);
}


m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
Expand All @@ -82,13 +90,110 @@ constructed yet. Thus, their requires() statements may grab null
*/
@Override
public void robotPeriodic() {
Scheduler.getInstance().run();

SmartDashboard.putNumber("X accel", navX.getRawAccelX());
SmartDashboard.putNumber("Y accel", navX.getRawAccelY());
SmartDashboard.putNumber("Z accel", navX.getRawAccelZ());

SmartDashboard.putNumber("X gyro", navX.getRawGyroX());
SmartDashboard.putNumber("Y gyro", navX.getRawGyroY());
SmartDashboard.putNumber("Z gyro", navX.getRawGyroZ());
/* Display 6-axis Processed Angle Data */
SmartDashboard.putBoolean("IMU_Connected", navX.isConnected());
SmartDashboard.putBoolean("IMU_IsCalibrating", navX.isCalibrating());
SmartDashboard.putNumber("IMU_Yaw", navX.getYaw());
SmartDashboard.putNumber("IMU_Pitch", navX.getPitch());
SmartDashboard.putNumber("IMU_Roll", navX.getRoll());

/* Display tilt-corrected, Magnetometer-based heading (requires */
/* magnetometer calibration to be useful) */

SmartDashboard.putNumber("IMU_CompassHeading", navX.getCompassHeading());

/* Display 9-axis Heading (requires magnetometer calibration to be useful) */
SmartDashboard.putNumber("IMU_FusedHeading", navX.getFusedHeading());

/* These functions are compatible w/the WPI Gyro Class, providing a simple */
/* path for upgrading from the Kit-of-Parts gyro to the navx-MXP */

SmartDashboard.putNumber("IMU_TotalYaw", navX.getAngle());
SmartDashboard.putNumber("IMU_YawRateDPS", navX.getRate());

/* Display Processed Acceleration Data (Linear Acceleration, Motion Detect) */

SmartDashboard.putNumber("IMU_Accel_X", navX.getWorldLinearAccelX());
SmartDashboard.putNumber("IMU_Accel_Y", navX.getWorldLinearAccelY());
SmartDashboard.putBoolean("IMU_IsMoving", navX.isMoving());
SmartDashboard.putBoolean("IMU_IsRotating", navX.isRotating());

/* Display estimates of velocity/displacement. Note that these values are */
/* not expected to be accurate enough for estimating robot position on a */
/* FIRST FRC Robotics Field, due to accelerometer noise and the compounding */
/* of these errors due to single (velocity) integration and especially */
/* double (displacement) integration. */

SmartDashboard.putNumber("Velocity_X", navX.getVelocityX());
SmartDashboard.putNumber("Velocity_Y", navX.getVelocityY());
SmartDashboard.putNumber("Displacement_X", navX.getDisplacementX());
SmartDashboard.putNumber("Displacement_Y", navX.getDisplacementY());

/* Display Raw Gyro/Accelerometer/Magnetometer Values */
/* NOTE: These values are not normally necessary, but are made available */
/* for advanced users. Before using this data, please consider whether */
/* the processed data (see above) will suit your needs. */

SmartDashboard.putNumber("RawGyro_X", navX.getRawGyroX());
SmartDashboard.putNumber("RawGyro_Y", navX.getRawGyroY());
SmartDashboard.putNumber("RawGyro_Z", navX.getRawGyroZ());
SmartDashboard.putNumber("RawAccel_X", navX.getRawAccelX());
SmartDashboard.putNumber("RawAccel_Y", navX.getRawAccelY());
SmartDashboard.putNumber("RawAccel_Z", navX.getRawAccelZ());
SmartDashboard.putNumber("RawMag_X", navX.getRawMagX());
SmartDashboard.putNumber("RawMag_Y", navX.getRawMagY());
SmartDashboard.putNumber("RawMag_Z", navX.getRawMagZ());
SmartDashboard.putNumber("IMU_Temp_C", navX.getTempC());

/* Omnimount Yaw Axis Information */
/* For more info, see http://navx-mxp.kauailabs.com/installation/omnimount */
AHRS.BoardYawAxis yaw_axis = navX.getBoardYawAxis();
SmartDashboard.putString("YawAxisDirection", yaw_axis.up ? "Up" : "Down");
SmartDashboard.putNumber("YawAxis", yaw_axis.board_axis.getValue());

/* Sensor Board Information */
SmartDashboard.putString("FirmwareVersion", navX.getFirmwareVersion());

/* Quaternion Data */
/* Quaternions are fascinating, and are the most compact representation of */
/* orientation data. All of the Yaw, Pitch and Roll Values can be derived */
/* from the Quaternions. If interested in motion processing, knowledge of */
/* Quaternions is highly recommended. */
SmartDashboard.putNumber("QuaternionW", navX.getQuaternionW());
SmartDashboard.putNumber("QuaternionX", navX.getQuaternionX());
SmartDashboard.putNumber("QuaternionY", navX.getQuaternionY());
SmartDashboard.putNumber("QuaternionZ", navX.getQuaternionZ());

/* Connectivity Debugging Support */
SmartDashboard.putNumber("IMU_Byte_Count", navX.getByteCount());
SmartDashboard.putNumber("IMU_Update_Count", navX.getUpdateCount());

// Puts the Elevator encoder position into Smart Dashboard
SmartDashboard.putNumber("Elevator Encoder", elevator.getElevatorEncoderPosition());
// Puts the Elevator error value into the Smart Dashboard
SmartDashboard.putNumber("Elevator Error", elevator.getElevatorError());
// Puts the Elevator set point value into the Smart Dashboard
SmartDashboard.putNumber("Elevator Set Point", elevator.getElevatorSetpoint());

// Puts the Bar encoder position into Smart Dashboard
SmartDashboard.putNumber("Bar Encoder", elevator.getBarEncoderPosition());
// Puts the Bar error value into the Smart Dashboard
SmartDashboard.putNumber("Bar Error", elevator.getBarError());
// Puts the Bar set point value into the Smart Dashboard
SmartDashboard.putNumber("Bar Set Point", elevator.getBarSetpoint());

if (ticks % 100 == 0) {
SmartDashboard.putNumber("ultra Distance", driveControl.getUltrasonicRange());
SmartDashboard.putBoolean("is range valid", DriveControl.ultra.isRangeValid());
}

ticks++;
}

/**
Expand Down Expand Up @@ -146,8 +251,8 @@ public void teleopPeriodic() {
}
// If the bot is at an angle of greater than 30 degrees then do elevator save.
if (navX.getRawGyroY() > 30) {
ElevatorSave elevatorSave = new ElevatorSave();
elevatorSave.start();
LiftSave liftSave = new LiftSave();
liftSave.start();
}
}

Expand Down

This file was deleted.

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import org.techvalleyhigh.frc5881.deepspace.robot.Robot;

/**
* Changes the elevator height
* Changes the lifts mode accordingly to the expected game piece to be receiving
*/
public class ElevatorFlip extends Command {

Expand All @@ -22,14 +22,12 @@ protected void initialize() {

@Override
protected void execute() {
if(!Robot.elevator.isFired){
Robot.elevator.elevatorFlip();
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This needs to be put back -- sort of. (Not sure what isFired is but....)

You need to put a boolean in the command to track to see if the command has already looped once through execute, (Default it to false, if false call .elevatorFlip() and set it to true, and in end() set it back to false. Just like you did in ElevatorDown.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This can be pulled out, so this is ok... but what is isFired doing? (And why is it being directly accessed?)

Robot.elevator.elevatorFlip();
}

@Override
protected boolean isFinished() {
return Robot.elevator.isSetpointReached();
return Robot.elevator.isElevatorSetpointReached();
}

/**
Expand Down
Loading