Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Drivetrain code #13

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
20 changes: 20 additions & 0 deletions src/com/nutrons/nu17/OperatorInterface.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,10 @@ public class OperatorInterface {
private final Button intakeSpit = new JoystickButton(OPERATOR_PAD, RobotMap.JOYSTICK_B);
private final Button raisePlacer = new JoystickButton(OPERATOR_PAD, RobotMap.JOYSTICK_Y);
private final Button lowerPlacer = new JoystickButton(OPERATOR_PAD, RobotMap.JOYSTICK_X);
private final Button getSlowDrivingMode =
new JoystickButton(DRIVER_PAD, RobotMap.JOYSTICK_LEFT_TRIGGER);
private final Button holdHeadingMode =
new JoystickButton(DRIVER_PAD, RobotMap.JOYSTICK_RIGHT_TRIGGER);

public static final Joystick DRIVER_PAD = new Joystick(RobotMap.JOYSTICK1);
public static final Joystick OPERATOR_PAD = new Joystick(RobotMap.JOYSTICK2);
Expand All @@ -37,6 +41,22 @@ public OperatorInterface() {
this.intakeSpit.whenPressed(new GroundIntakeSpitCmd());
}

/**
*
* @return Will return true if button is being held, false if not.
*/
public boolean getHoldHeadingMode() {
return this.holdHeadingMode.get();
}

/**
*
* @return Will return true if button is being held, false if not.
*/
public boolean getSlowDrivingMode() {
return this.getSlowDrivingMode.get();
}

/**
* @return driver's left joystick y value.
*/
Expand Down
2 changes: 0 additions & 2 deletions src/com/nutrons/nu17/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,13 @@
import com.nutrons.nu17.subsystems.GearPlacer;
import com.nutrons.nu17.subsystems.GroundIntake;
import com.nutrons.nu17.subsystems.Shooter;
import com.nutrons.nu17.subsystems.TwinShooter;

import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;

public class Robot extends IterativeRobot {

public static final TwinShooter TWIN_SHOOTER = new TwinShooter();
public static final Shooter SHOOTER = new Shooter();
public static final GroundIntake GROUND_INTAKE = new GroundIntake();
public static final GearPlacer GP = new GearPlacer();
Expand Down
54 changes: 31 additions & 23 deletions src/com/nutrons/nu17/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@ public class RobotMap {

// Ports of wheels
public static final int FRONT_LEFT = 0;
public static final int BACK_LEFT = 1;
public static final int FRONT_RIGHT = 2;
public static final int BACK_RIGHT = 3;
// Paramter naming convention : Subsystem SIDE_PLACEMENT
public static final int BACK_LEFT = 0;
public static final int FRONT_RIGHT = 0;
public static final int BACK_RIGHT = 0;

// Ports of intake
public static final int ROLLER_FRONT = 0;
public static final int ROLLER_BACK = 0;
Expand All @@ -18,7 +18,7 @@ public class RobotMap {

// Ports of Ultrasonics
public static final int ULTRASONIC_RX = 0;
public static final int ULTRASONIC_TX = 1;
public static final int ULTRASONIC_TX = 0;

// Port of gyro
public static final int DRIVETRAIN_HEADING_GYRO = 0;
Expand All @@ -36,32 +36,40 @@ public class RobotMap {
public static final int CLIMBER_MICRO_SWITCH = 0;

// Ports of encoders
public static final int LEFT_WHEEL_DRIVE_DISTANCE_ENCODER_1 = 1;
public static final int LEFT_WHEEL_DRIVE_DISTANCE_ENCODER_2 = 2;
public static final int RIGHT_WHEEL_DRIVE_DISTANCE_ENCODER_1 = 1;
public static final int RIGHT_WHEEL_DRIVE_DISTANCE_ENCODER_2 = 2;
public static final int FLY_ENCODER_FRONT_RIGHT = 5;
public static final int FLY_ENCODER_BACK_RIGHT = 6;
public static final int FLY_ENCODER_FRONT_LEFT = 7;
public static final int FLY_ENCODER_BACK_LEFT = 8;
public static final int TWIN_LEFT_ENCODER_1 = 9;
public static final int TWIN_LEFT_ENCODER_2 = 10;
public static final int TWIN_RIGHT_ENCODER_1 = 11;
public static final int TWIN_RIGHT_ENCODER_2 = 12;
public static final int LEFT_WHEEL_DRIVE_DISTANCE_ENCODER_1 = 0;
public static final int LEFT_WHEEL_DRIVE_DISTANCE_ENCODER_2 = 0;
public static final int RIGHT_WHEEL_DRIVE_DISTANCE_ENCODER_1 = 0;
public static final int RIGHT_WHEEL_DRIVE_DISTANCE_ENCODER_2 = 0;
public static final int FLY_ENCODER_FRONT_RIGHT = 0;
public static final int FLY_ENCODER_BACK_RIGHT = 0;
public static final int FLY_ENCODER_FRONT_LEFT = 0;
public static final int FLY_ENCODER_BACK_LEFT = 0;
public static final int TWIN_LEFT_ENCODER_1 = 0;
public static final int TWIN_LEFT_ENCODER_2 = 0;
public static final int TWIN_RIGHT_ENCODER_1 = 0;
public static final int TWIN_RIGHT_ENCODER_2 = 0;
public static final int SHOOT_ENCODER_1 = 0;
public static final int SHOOT_ENCODER_2 = 1;
public static final int SHOOT_ENCODER_2 = 0;


// Port of joysticks
public static final int JOYSTICK1 = 0;
public static final int JOYSTICK2 = 1;
public static final int JOYSTICK2 = 0;

// Buttons
// TODO: Needs tune testing
public static final int JOYSTICK_A = 0;
public static final int JOYSTICK_B = 1;
public static final int JOYSTICK_X = 2;
public static final int JOYSTICK_Y = 3;
public static final int JOYSTICK_LEFT_BUMPER = 4;
public static final int JOYSTICK_B = 0;
public static final int JOYSTICK_X = 0;
public static final int JOYSTICK_Y = 0;
public static final int JOYSTICK_LEFT_BUMPER = 0;
public static final int JOYSTICK_LEFT_TRIGGER = 0;
public static final int JOYSTICK_RIGHT_BUMPER = 0;
public static final int JOYSTICK_RIGHT_TRIGGER = 0;
public static final int JOYSTICK_DPAD_UP = 0;
public static final int JOYSTICK_DPAD_DOWN = 0;
public static final int JOYSTICK_DPAD_LEFT = 0;
public static final int JOYSTICK_DPAD_RIGHT = 0;

// TODO tune this constant for deadband
public static final double JOYSTICK_DEADBAND = 0.05;
Expand Down
35 changes: 35 additions & 0 deletions src/com/nutrons/nu17/commands/DriveCheesyCmd.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
package com.nutrons.nu17.commands;

import com.nutrons.nu17.Robot;

import edu.wpi.first.wpilibj.command.Command;

/**
* Command for CheesyDrive drive type.
*/
public class DriveCheesyCmd extends Command {

public DriveCheesyCmd() {
requires(Robot.DRIVETRAIN);
}

protected void initialize() {
Robot.DRIVETRAIN.driveCheesy(Robot.OperatorInterface.getLeftJoystickY(),
Robot.OperatorInterface.getRightJoystickX(), Robot.OperatorInterface.getHoldHeadingMode());
}


protected void execute() {

}

protected boolean isFinished() {
return false;
}


protected void end() {}


protected void interrupted() {}
}
41 changes: 0 additions & 41 deletions src/com/nutrons/nu17/commands/ShootTwinShooterCmd.java

This file was deleted.

Loading