Skip to content

Commit

Permalink
CAN ID 4 Talon giving problems on drive train, replaced with CAN ID 2…
Browse files Browse the repository at this point in the history
… Talon
  • Loading branch information
Acelogic committed Mar 31, 2017
1 parent e951196 commit 1e0f4cc
Show file tree
Hide file tree
Showing 8 changed files with 45 additions and 141 deletions.
11 changes: 3 additions & 8 deletions src/org/usfirst/frc/team1635/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@

import org.usfirst.frc.team1635.robot.commands.BottomOutElevator;


import org.usfirst.frc.team1635.robot.commands.ShootBalls;
import org.usfirst.frc.team1635.robot.commands.WiggleForward;
//Local Package Imports
import org.usfirst.frc.team1635.util.XboxControllerButton;
Expand Down Expand Up @@ -52,8 +50,8 @@ public class OI {
DPadButton dPadLeft = new DPadButton(gameController, DPadButton.Direction.Left);
DPadButton dPadRight = new DPadButton(gameController, DPadButton.Direction.Right);

// -----------------------------------------------------------------------------------
// For DualControllers
// -----------------------------------------------------------------------------------
// For DualControllers
public boolean globalA;
public boolean globalB;
public boolean globalX;
Expand Down Expand Up @@ -87,16 +85,13 @@ public void masterToSecondary(XboxController master, XboxController secondary) {
this.globalStartButton = master.getStartButton() || secondary.getStartButton();
}

// ---------------------------------------------------------------------------------------
// ---------------------------------------------------------------------------------------

public OI() {
aButton.whenPressed(new WiggleForward());
aButton2.whenPressed(new WiggleForward());
// Don't use B - we switch camera with it.

dPadUp.whenPressed(new ShootBalls());
dPadUp2.whenPressed(new ShootBalls());

dPadDown.whenPressed(new BottomOutElevator());
dPadDown2.whenPressed(new BottomOutElevator());
// dPadLeft.whenPressed(new PopGearWithFlapsDown());
Expand Down
4 changes: 2 additions & 2 deletions src/org/usfirst/frc/team1635/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,9 @@ public class RobotMap {
// ------------------------------------------------------------
// CAN IDs/Ports
public static int elevatorMotorCANPort = 3;
public static int elevatorRollerMotorCANPort = 2;
public static int elevatorRollerMotorCANPort;
// Drive
public static int frontLeftMotorCANPort = 4;
public static int frontLeftMotorCANPort = 2; // 4 Died Replacing with 2
public static int frontRightMotorCANPort = 6;
public static int backLeftMotorCANPort = 1;
public static int backRightMotorCANPort = 5;
Expand Down
76 changes: 0 additions & 76 deletions src/org/usfirst/frc/team1635/robot/commands/ShootBalls.java

This file was deleted.

73 changes: 36 additions & 37 deletions src/org/usfirst/frc/team1635/robot/control/ControlDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
import edu.wpi.first.wpilibj.command.Command;
//------------------------------------------------------------


//.---. ,--. .-----. .------.
///_ | / .' / -. \| ___|
//| |. / -. '-' _' || '--.
Expand All @@ -17,42 +16,42 @@
//`---' `----' `----'' `----''

/**
*
* @author Bogdan Bradu & Miguel Cruz ( @Acelogic_)
*
*/
*
* @author Bogdan Bradu & Miguel Cruz ( @Acelogic_)
*
*/
public class ControlDrive extends Command {

public ControlDrive() {
// Use requires() here to declare subsystem dependencies
requires(Robot.chassisSystem);
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.chassisSystem.drive();
Robot.chassisSystem.log();
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}

// Called once after isFinished returns true
protected void end() {
Robot.chassisSystem.stop();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
public ControlDrive() {
// Use requires() here to declare subsystem dependencies
requires(Robot.chassisSystem);

}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.oi.masterToSecondary(Robot.oi.StartController(), Robot.oi.StartController2());
Robot.chassisSystem.drive();
Robot.chassisSystem.log();

}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return false;
}

// Called once after isFinished returns true
protected void end() {
Robot.chassisSystem.stop();
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ protected void initialize() {
// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.elevatorSystem.controlElevator();
Robot.elevatorSystem.elevatorRollerControl();
Robot.elevatorSystem.log();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@ protected void initialize() {

// Called repeatedly when this Command is scheduled to run
protected void execute() {

Robot.pneumaticsSystem.shiftDriveGears();
Robot.elevatorSystem.controlFlaps();
Robot.pneumaticsSystem.log();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ public class ElevatorSubsystem extends Subsystem {
public ElevatorSubsystem() {
super();
elevatorActuator = new CANTalon(RobotMap.elevatorMotorCANPort);
elevatorRoller = new CANTalon(RobotMap.elevatorRollerMotorCANPort);

limitSwitchTop = new DigitalInput(RobotMap.topLimitSwitchDioPort);
limitSwitchBottom = new DigitalInput(RobotMap.bottomLimitSwitchDioPort);
analogPot = new AnalogPotentiometer(RobotMap.potentiometerAnalogPort, 3600.0 / 5);
Expand Down Expand Up @@ -74,9 +74,6 @@ public void controlElevator() {
} else if (Robot.oi.StartController().getTriggerAxis(Hand.kRight) > .3) {
if (isElevatorAtDangerSpot()) {
stopElevator();
Timer.delay(0.2);
setElevatorSpeed(-0.15);
Timer.delay(1.25);
}

else {
Expand All @@ -95,15 +92,6 @@ public void controlElevator() {
}
}

public void elevatorRollerControl() {
if (Robot.oi.globalX) {
elevatorRoller.set(1);

} else {
elevatorRoller.set(0);
}
}

public void controlFlaps() {
if (Robot.oi.globalStartButton) {
moveFlapsDown();
Expand Down Expand Up @@ -161,7 +149,7 @@ public boolean isElevatorAtSweetSpot() {
}

public boolean isElevatorAtDangerSpot() {
if (Math.abs(getPotentiometerValue() - 520.0) <= 5) {
if (Math.abs(getPotentiometerValue() - 394.0) <= 5) {
return true;
} else {
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ public void initDefaultCommand() {
public void operateWinch() {

if (Robot.oi.globalBackButton) {
rollerTalonSR.set(-1);
rollerTalonSRx2.set(-1);
rollerTalonSR.set(1);
rollerTalonSRx2.set(1);
} else if (!Robot.oi.globalBackButton) {
stopWinch();
}
Expand Down

0 comments on commit 1e0f4cc

Please sign in to comment.