Skip to content

Commit

Permalink
Merge pull request #60 from blair-robot-project/whitman_merge
Browse files Browse the repository at this point in the history
Whitman merge
  • Loading branch information
rytse authored Mar 15, 2017
2 parents 8a262b7 + d17f577 commit 22a4162
Show file tree
Hide file tree
Showing 111 changed files with 7,010 additions and 1,907 deletions.
14 changes: 8 additions & 6 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ protobuf {
// options. Note the braces cannot be omitted, otherwise the
// plugin will not be added. This is because of the implicit way
// NamedDomainObjectContainer binds the methods.
grpc { }
grpc {}
}
}
}
Expand All @@ -82,7 +82,7 @@ idea {
}
}

task convertFiles{
task convertFiles {
doLast {
fileTree("./src/main/resources").matching { include "*" }.each { aFile ->
exec {
Expand All @@ -94,14 +94,16 @@ task convertFiles{
}

frc {
//deployers += [to: "/home/lvuser/map.cfg", from: './src/main/resources/map.cfg']
//deployers += [to: "/home/lvuser/profile.csv", from: './src/main/resources/profile.csv']
// deployers += [to: "/home/lvuser/map.cfg", from: './src/main/resources/map.cfg']
// deployers += [to: "/home/lvuser/profile.csv", from: './src/main/resources/profile.csv']
// deployers += [to: "/home/lvuser/profile.csv", from: './src/main/resources/profile.csv']
team = '449'
robotClass = "org.usfirst.frc.team449.robot.Robot"
}

wpi {
wpilibVersion = "+" // The WPILib version to use. For this version of GradleRIO, must be a 2017 version
wpilibVersion = "+"
// The WPILib version to use. For this version of GradleRIO, must be a 2017 version
ntcoreVersion = "+" // The NetworkTables Core version to use.
opencvVersion = "+" // The OpenCV version to use
cscoreVersion = "+" // The CSCore version to use
Expand All @@ -124,7 +126,7 @@ task genJavadoc(type: Jar, dependsOn: javadoc) {
from javadoc.destinationDir
}

task('copyResources', dependsOn: convertFiles){
task('copyResources', dependsOn: convertFiles) {
doLast {
ssh.run {
session(remotes.rio) {
Expand Down
Binary file modified gradle/wrapper/gradle-wrapper.jar
Binary file not shown.
4 changes: 2 additions & 2 deletions gradle/wrapper/gradle-wrapper.properties
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#Wed Feb 15 17:39:11 EST 2017
#Tue Mar 07 16:17:41 EST 2017
distributionBase=GRADLE_USER_HOME
distributionPath=wrapper/dists
zipStoreBase=GRADLE_USER_HOME
zipStorePath=wrapper/dists
distributionUrl=https\://services.gradle.org/distributions/gradle-3.3-bin.zip
distributionUrl=https\://services.gradle.org/distributions/gradle-3.3-all.zip
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ public abstract class ReferencingCommandGroup extends CommandGroup {
/**
* Subsystem to reference to
*/
MappedSubsystem subsystem;
private MappedSubsystem subsystem;

/**
* Instantiate the ReferencingCommandGroup
Expand Down
104 changes: 89 additions & 15 deletions src/main/java/org/usfirst/frc/team449/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,18 @@
import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import maps.org.usfirst.frc.team449.robot.Robot2017Map;
import org.usfirst.frc.team449.robot.drive.talonCluster.TalonClusterDrive;
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.DefaultArcadeDrive;
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.ExecuteProfile;
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.PIDTest;
import org.usfirst.frc.team449.robot.drive.talonCluster.commands.SwitchToLowGear;
import org.usfirst.frc.team449.robot.mechanism.climber.ClimberSubsystem;
import org.usfirst.frc.team449.robot.mechanism.feeder.FeederSubsystem;
import org.usfirst.frc.team449.robot.mechanism.intake.Intake2017.Intake2017;
import org.usfirst.frc.team449.robot.mechanism.intake.Intake2017.commands.updown.IntakeUp;
import org.usfirst.frc.team449.robot.mechanism.intake.IntakeSubsystem;
import org.usfirst.frc.team449.robot.mechanism.pneumatics.PneumaticsSubsystem;
import org.usfirst.frc.team449.robot.mechanism.singleflywheelshooter.SingleFlywheelShooter;
import org.usfirst.frc.team449.robot.oi.OI2017ArcadeGamepad;
Expand All @@ -18,111 +23,180 @@
import java.io.IOException;

/**
* Created by BlairRobot on 2017-01-08.
* The main class of the robot, constructs all the subsystems and initializes default commands.
*/
public class Robot extends IterativeRobot {

/**
* The shooter subsystem (flywheel only)
*/
public static SingleFlywheelShooter singleFlywheelShooterSubsystem;

/**
* The intake subsystem (intake motors and pistons)
*/
public static Intake2017 intakeSubsystem;

/**
*The climber
*/
public static ClimberSubsystem climberSubsystem;

/**
*The pneumatics (maybe doesn't work?)
*/
public static PneumaticsSubsystem pneumaticsSubsystem;

/**
*The drive
*/
public static TalonClusterDrive driveSubsystem;

/**
* OI, using an Xbox-style controller and arcade drive.
*/
public static OI2017ArcadeGamepad oiSubsystem;

/**
* The cameras on the robot and the code to stream them to SmartDashboard (NOT computer vision!)
*/
public static CameraSubsystem cameraSubsystem;

/**
* The auger used to feed balls into the shooter.
*/
public static FeederSubsystem feederSubsystem;

private static maps.org.usfirst.frc.team449.robot.Robot2017Map.Robot2017 cfg;
/**
* The object constructed directly from map.cfg.
* */
private static Robot2017Map.Robot2017 cfg;

/**
* The method that runs when the robot is turned on. Initializes all subsystems from the map.
*/
public void robotInit() {
System.out.println("Started robotInit");
System.out.println("Started robotInit.");

try {
//Try to construct map from the cfg file
//cfg = (Robot2017Map.Robot2017) MappedSubsystem.readConfig("/home/lvuser/449_resources/balbasaur_map.cfg",
cfg = (Robot2017Map.Robot2017) MappedSubsystem.readConfig("/home/lvuser/449_resources/final_map.cfg",
//cfg = (Robot2017Map.Robot2017) MappedSubsystem.readConfig("/home/lvuser/449_resources/final_map_only_drive.cfg",
//cfg = (Robot2017Map.Robot2017) MappedSubsystem.readConfig("/home/lvuser/449_resources/final_map.cfg",
cfg = (Robot2017Map.Robot2017) MappedSubsystem.readConfig("/home/lvuser/449_resources/fancy_map.cfg",
Robot2017Map.Robot2017.newBuilder());
} catch (IOException e) {
//This is either the map file not being in the file system OR it being improperly formatted.
System.out.println("Config file is bad/nonexistent!");
e.printStackTrace();
}

//Construct the OI (has to be done first because other subsystems take the OI as an argument.)
oiSubsystem = new OI2017ArcadeGamepad(cfg.getArcadeOi());
System.out.println("Constructed OI");

//Construct the drive (not in a if block because you kind of need it.)
driveSubsystem = new TalonClusterDrive(cfg.getDrive(), oiSubsystem);
System.out.println("Constructed Drive");

//Construct camera if it's in the map.
if (cfg.hasCamera()) {
cameraSubsystem = new CameraSubsystem(cfg.getCamera());
}

//Construct climber if it's in the map.
if (cfg.hasClimber()) {
climberSubsystem = new ClimberSubsystem(cfg.getClimber());
}

//Construct shooter if it's in the map.
if (cfg.hasShooter()) {
singleFlywheelShooterSubsystem = new SingleFlywheelShooter(cfg.getShooter());
System.out.println("Constructed SingleFlywheelShooter");
}

// pneumaticsSubsystem = new PneumaticsSubsystem(cfg.getPneumatics());
// System.out.println("Constructed PneumaticsSubsystem");

//Construct pneumatics if it's in the map.
if (cfg.hasPneumatics()) {
pneumaticsSubsystem = new PneumaticsSubsystem(cfg.getPneumatics());
System.out.println("Constructed PneumaticsSubsystem");
}

//Construct intake if it's in the map.
if (cfg.hasIntake()) {
intakeSubsystem = new Intake2017(cfg.getIntake());
}

if (cfg.hasFeeder()){
//Construct feeder if it's in the map.
if (cfg.hasFeeder()) {
feederSubsystem = new FeederSubsystem(cfg.getFeeder());
}

//Map the buttons (has to be done last because all the subsystems need to have been instantiated.)
oiSubsystem.mapButtons();
System.out.println("Mapped buttons");

//Activate the compressor if its module number is in the map.
if (cfg.hasModule()) {
Compressor compressor = new Compressor(cfg.getModule());
compressor.setClosedLoopControl(true);
compressor.start();
}
}

/**
* Run when we first enable in teleop.
*/
@Override
public void teleopInit() {
// if (driveSubsystem.shifter != null) {
// Scheduler.getInstance().add(new SwitchToHighGear(driveSubsystem));
// }
//Stop the drive for safety reasons
driveSubsystem.setVBusThrottle(0, 0);

driveSubsystem.setDefaultThrottle(0, 0);
driveSubsystem.leftMaster.canTalon.enable();
driveSubsystem.rightMaster.canTalon.enable();

if (driveSubsystem.shifter != null){
//Switch to low gear if we have gears
if (driveSubsystem.shifter != null) {
Scheduler.getInstance().add(new SwitchToLowGear(driveSubsystem));
}

if (intakeSubsystem != null) {
Scheduler.getInstance().add(new IntakeUp(intakeSubsystem));
}

// Scheduler.getInstance().add(new DefaultArcadeDrive(driveSubsystem.straightPID, driveSubsystem, oiSubsystem));
}

/**
* Run every tick in teleop.
*/
@Override
public void teleopPeriodic() {
//Run all commands. This is a WPILib thing you don't really have to worry about.
Scheduler.getInstance().run();
}

/**
* Run when we first enable in autonomous
*/
@Override
public void autonomousInit() {
driveSubsystem.setDefaultThrottle(0, 0);
//Set throttle to 0 for safety reasons
if (driveSubsystem.shifter != null) {
Scheduler.getInstance().add(new SwitchToLowGear(driveSubsystem));
}
driveSubsystem.leftMaster.canTalon.enable();
driveSubsystem.rightMaster.canTalon.enable();
driveSubsystem.setVBusThrottle(0, 0);
Scheduler.getInstance().add(new PIDTest(driveSubsystem));
// Scheduler.getInstance().add(new ExecuteProfile(driveSubsystem));
}

/**
* Runs every tick in autonomous.
*/
@Override
public void autonomousPeriodic() {
//Run all commands. This is a WPILib thing you don't really have to worry about.
Scheduler.getInstance().run();
SmartDashboard.putNumber("Heading", driveSubsystem.getGyroOutput());
}
}
15 changes: 0 additions & 15 deletions src/main/java/org/usfirst/frc/team449/robot/Tester2017.java

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,10 @@
* A subsystem that has a NavX on it.
*/
public interface NavxSubsystem {
/**
* Get the output of the NavX
*
* @return The heading, on a scale of -180 to 180.
*/
double getGyroOutput();
}
Loading

0 comments on commit 22a4162

Please sign in to comment.