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

Not Splines #28

Open
wants to merge 33 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 27 commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
8d974b8
Code for the chassis
joshuatehrlich Jan 14, 2019
8f83181
merged master
joshuatehrlich Jan 14, 2019
d75d6a7
uncommented a thing
joshuatehrlich Jan 14, 2019
3973dd3
fixed a thing
joshuatehrlich Jan 14, 2019
1d20676
Added driving PID
Jan 18, 2019
5ea0ede
Made PR changes
Jan 20, 2019
81e0953
Fixed PR Changes
Jan 20, 2019
e4c2e6e
Fixed PR Comment
Jan 20, 2019
e9a104f
Fixed PR Comment
Jan 20, 2019
28665f6
made the class NotSplines, which is a base for having the robot drive…
Jan 29, 2019
a3126b3
i don't even know
Feb 3, 2019
7b6b6ce
i think i finished, the robot should turn the specified angle and the…
Feb 3, 2019
f430ddc
networktables stuff
Feb 3, 2019
6c08112
added an autonly folder and some new code stuff in it
Krakavius Feb 14, 2019
3cfb65d
fixed up/added to the math
Krakavius Feb 14, 2019
bfe275c
networktables stuff including a new class that uses them.
Krakavius Feb 15, 2019
ffc4405
massive changes mostly to networktablesauton, boringauton also update…
Krakavius Feb 16, 2019
5fd6a9c
standard stuff
Krakavius Feb 16, 2019
3ed7f08
leo cucked the code
Krakavius Feb 16, 2019
be0940d
changed stuff in the classes and deleted interestingauton.java since …
Krakavius Feb 16, 2019
8eda0a0
moved networktables stuff to robotmap so we can choose when to update…
Krakavius Feb 17, 2019
bbd0b48
edited code so robot should always be able to see tapes when it needs to
Krakavius Feb 17, 2019
03fbfbd
complete overhaul including new classes
Krakavius Feb 17, 2019
0d5f5c9
made a config class, finished up 3 routines (hopefully)
Krakavius Feb 17, 2019
f564659
fixed some minor syntax stuff and made notsplines.java work correctly.
Krakavius Feb 18, 2019
8f58d53
made the UpdateableData.java file and worked with rohan to add CAN su…
Krakavius Feb 18, 2019
ba50434
sovereingity
Krakavius Feb 19, 2019
f905d82
fixed some requested changes
Krakavius Feb 19, 2019
069dca3
i guess some robotmap import stuff
Krakavius Mar 1, 2019
fc45e57
standard stuff
Krakavius Mar 3, 2019
3348964
standard stuff
Krakavius Mar 3, 2019
3373ca4
removed sovereignty
Krakavius Mar 3, 2019
2c9636c
renamed boringauton to autoalign
Krakavius Mar 4, 2019
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
13 changes: 8 additions & 5 deletions src/main/java/org/usfirst/frc4904/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Copy link
Member

Choose a reason for hiding this comment

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

you don't need to change robot.java in this PR

Copy link
Member

Choose a reason for hiding this comment

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

checkout master's version of Robot.java

import org.usfirst.frc4904.standard.CommandRobotBase;
import org.usfirst.frc4904.standard.commands.chassis.ChassisMove;
import org.usfirst.frc4904.robot.humaninterface.drivers.NathanGain;
import org.usfirst.frc4904.robot.humaninterface.operators.DefaultOperator;
import edu.wpi.first.cameraserver.CameraServer;;


Expand All @@ -22,8 +24,8 @@ public class Robot extends CommandRobotBase {

@Override
public void initialize() {
// driverChooser.addDefault(object);
// operatorChooser.addDefault();
driverChooser.addDefault(new NathanGain());
operatorChooser.addDefault(new DefaultOperator());
/*
works in shuffleboard with Logitech C270
any amount of compression, 30 FPS, 160 x 120
Expand All @@ -35,8 +37,8 @@ public void initialize() {

@Override
public void teleopInitialize() {
// teleopCommand = new ChassisMove(RobotMap.Component.chassis, driverChooser.getSelected());
// teleopCommand.start();
teleopCommand = new ChassisMove(RobotMap.Component.chassis, driverChooser.getSelected());
teleopCommand.start();
}

@Override
Expand All @@ -61,5 +63,6 @@ public void testInitialize() {}
public void testExecute() {}

@Override
public void alwaysExecute() {}
public void alwaysExecute() {
}
}
152 changes: 142 additions & 10 deletions src/main/java/org/usfirst/frc4904/robot/RobotMap.java
Original file line number Diff line number Diff line change
@@ -1,32 +1,164 @@
package org.usfirst.frc4904.robot;

import org.usfirst.frc4904.standard.custom.controllers.CustomJoystick;
import org.usfirst.frc4904.standard.custom.controllers.CustomXbox;
import org.usfirst.frc4904.robot.humaninterface.HumanInterfaceConfig;
import org.usfirst.frc4904.standard.subsystems.chassis.TankDriveShifting;
import org.usfirst.frc4904.standard.subsystems.chassis.SolenoidShifters;
import org.usfirst.frc4904.standard.subsystems.motor.Motor;
import org.usfirst.frc4904.standard.subsystems.motor.speedmodifiers.EnableableModifier;
import org.usfirst.frc4904.standard.subsystems.motor.speedmodifiers.AccelerationCap;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.NetworkTableInstance;

import org.usfirst.frc4904.standard.custom.sensors.PDP;
import org.usfirst.frc4904.standard.custom.PCMPort;
//import org.usfirst.frc4904.standard.custom.sensors.CANEncoder;
Copy link
Member

Choose a reason for hiding this comment

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

Don't have commented out code in a PR

//import org.usfirst.frc4904.standard.custom.sensors.EncoderPair;
import org.usfirst.frc4904.standard.custom.motioncontrollers.CANTalonSRX;
import org.usfirst.frc4904.standard.custom.motioncontrollers.CustomPIDController;
import org.usfirst.frc4904.standard.custom.sensors.NavX;



public class RobotMap {
public static class Port {
public static class HumanInput {
public static final int joystick = 0;
public static final int xboxController = 1;

}
public static class CANMotor {}
public static class PWM {}
public static class CAN {}
public static class Pneumatics {}
public static class PWM {
public static final int leftDriveA = -1; // TODO: Change ports
public static final int leftDriveB = -1;
public static final int rightDriveA = -1;
public static final int rightDriveB = -1;
}
public static class CAN {
//public static final int leftEncoder = -1; // TODO: Change ports
//public static final int rightEncoder = -1;
}
public static class Pneumatics {
public static final PCMPort shifter = new PCMPort(-1, -1, -1); // TODO: Change ports
}
}

public static class Metrics{}
public static class Component {
public static CustomXbox driverXbox;
public static class Metrics{
public static class Wheel {
public static final double TICKS_PER_REVOLUTION = 4.904; // Obviously not real metrics
public static final double DIAMETER_INCHES = 4.904;
public static final double CIRCUMFERENCE_INCHES = Metrics.Wheel.DIAMETER_INCHES * Math.PI;
public static final double TICKS_PER_INCH = Metrics.Wheel.TICKS_PER_REVOLUTION
/ Metrics.Wheel.CIRCUMFERENCE_INCHES;
public static final double DISTANCE_FRONT_BACK = 4.904;
public static final double DISTANCE_SIDE_SIDE = 4.904;
public static final double INCHES_PER_TICK = Metrics.Wheel.CIRCUMFERENCE_INCHES
/ Metrics.Wheel.TICKS_PER_REVOLUTION;
}
public static class Robot {
public static final double ROBOT_WIDTH = 28;
}
}
public static class PID {
public static class Drive {
public static final double P = 0.04; //Tune PID
Copy link
Member

Choose a reason for hiding this comment

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

just set to -1

public static final double I = 0.0; //Tune PID
public static final double D = -0.006; //Tune PID
public static final double F = 0.01; //Tune PID
public static final double tolerance = 4.5; //Tune PID
public static final double dTolerance = 3.0; //Tune PID
}
}
public static class Component {
public static PDP pdp;

public static TankDriveShifting chassis;
public static Motor leftWheel;
public static Motor rightWheel;
public static SolenoidShifters shifter;
public static EnableableModifier rightWheelAccelerationCap;
public static EnableableModifier leftWheelAccelerationCap;

//public static CANEncoder leftWheelEncoder;
//public static CANEncoder rightWheelEncoder;
//public static EncoderPair chassisEncoders;
public static CustomPIDController chassisTurnMC;
public static CustomPIDController drivePID;
public static NavX navx;
}

public static class NetworkTables {
public static NetworkTableInstance inst;
public static NetworkTable table;

public static class Sensors {
public static NetworkTable table;
public static NetworkTableEntry betaRF;
public static NetworkTableEntry betaFloor;
public static NetworkTableEntry theta;
public static NetworkTableEntry x;
public static NetworkTableEntry y;
public static NetworkTableEntry distance;
public static NetworkTableEntry isRFTapeVisible;
public static NetworkTableEntry isFloorTapeVisible;
}

public static class PID {
public static NetworkTable table;

}
}

public static class HumanInput {
public static class Driver {
public static CustomXbox xbox;
}
public static class Operator {}
}
public static class Operator {
public static CustomJoystick joystick;
}
}

public RobotMap() {
Component.driverXbox = new CustomXbox(Port.HumanInput.xboxController);
Component.driverXbox.setDeadZone(0.1);
Component.pdp = new PDP();

// Wheels
// Component.leftWheelEncoder = new CANEncoder("LeftEncoder", Port.CAN.leftEncoder);
// Component.rightWheelEncoder = new CANEncoder("RightEncoder", Port.CAN.rightEncoder);
// Component.leftWheelEncoder.setDistancePerPulse(Metrics.Wheel.INCHES_PER_TICK);
// Component.rightWheelEncoder.setDistancePerPulse(Metrics.Wheel.INCHES_PER_TICK);
Component.leftWheelAccelerationCap = new EnableableModifier(new AccelerationCap(Component.pdp));
Component.leftWheelAccelerationCap.enable();
Component.rightWheelAccelerationCap = new EnableableModifier(new AccelerationCap(Component.pdp));
Component.rightWheelAccelerationCap.enable();
Component.leftWheel = new Motor("LeftWheel", Component.leftWheelAccelerationCap,
new CANTalonSRX(Port.PWM.leftDriveA), new CANTalonSRX(Port.PWM.leftDriveB));
Component.rightWheel = new Motor("RightWheel", Component.rightWheelAccelerationCap,
new CANTalonSRX(Port.PWM.rightDriveA), new CANTalonSRX(Port.PWM.rightDriveB));

NetworkTables.inst = NetworkTableInstance.getDefault();
NetworkTables.Sensors.table = NetworkTables.inst.getTable("Sensors");
NetworkTables.Sensors.betaRF = NetworkTables.Sensors.table.getEntry("RF Beta");
NetworkTables.Sensors.betaFloor = NetworkTables.Sensors.table.getEntry("Floor Beta");
NetworkTables.Sensors.theta = NetworkTables.Sensors.table.getEntry("Theta");
NetworkTables.Sensors.x = NetworkTables.Sensors.table.getEntry("X");
NetworkTables.Sensors.y = NetworkTables.Sensors.table.getEntry("Y");
NetworkTables.Sensors.distance = NetworkTables.Sensors.table.getEntry("Distance");
NetworkTables.Sensors.isRFTapeVisible = NetworkTables.Sensors.table.getEntry("Is RF Tape Visible?");
NetworkTables.Sensors.isFloorTapeVisible = NetworkTables.Sensors.table.getEntry("Is Floor Tape Visible?");

// Chassis
Component.shifter = new SolenoidShifters(Port.Pneumatics.shifter.pcmID, Port.Pneumatics.shifter.forward,
Port.Pneumatics.shifter.reverse);
//Component.chassisEncoders = new EncoderPair(Component.leftWheelEncoder, Component.rightWheelEncoder);
Component.chassis = new TankDriveShifting("2019-Chassis", Component.leftWheel, Component.rightWheel, Component.shifter);
HumanInput.Driver.xbox = new CustomXbox(Port.HumanInput.xboxController);
HumanInput.Driver.xbox.setDeadZone(HumanInterfaceConfig.XBOX_DEADZONE);
HumanInput.Operator.joystick = new CustomJoystick(Port.HumanInput.joystick);
HumanInput.Operator.joystick.setDeadzone(HumanInterfaceConfig.JOYSTICK_DEADZONE);
//Component.drivePID = new CustomPIDController(PID.Drive.P, PID.Drive.I, PID.Drive.D, PID.Drive.F, Component.rightWheelEncoder);
Component.drivePID.setAbsoluteTolerance(PID.Drive.tolerance);
Component.drivePID.setDerivativeTolerance(PID.Drive.dTolerance);
}
}
15 changes: 15 additions & 0 deletions src/main/java/org/usfirst/frc4904/robot/autonly/AutonConfig.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
package org.usfirst.frc4904.robot.autonly;

import org.usfirst.frc4904.robot.RobotMap;

public class AutonConfig {
public enum VisionInterfaceType {
NETWORK_TABLES,
CAN
}

public static final double DRIVE_TOLERANCE = RobotMap.Metrics.Robot.ROBOT_WIDTH / 2;
public static final double MINIMUM_VISION_DISTANCE = 18.0;
public static final double NO_CLOSER = Math.max(DRIVE_TOLERANCE, MINIMUM_VISION_DISTANCE);
public static final VisionInterfaceType VISION_INTERFACE_TYPE = VisionInterfaceType.NETWORK_TABLES;
}
40 changes: 40 additions & 0 deletions src/main/java/org/usfirst/frc4904/robot/autonly/BoringAuton.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package org.usfirst.frc4904.robot.autonly;

import org.usfirst.frc4904.standard.commands.chassis.ChassisTurn;
import org.usfirst.frc4904.standard.commands.chassis.ChassisMoveDistance;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import org.usfirst.frc4904.robot.RobotMap;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.CommandGroup;
import org.usfirst.frc4904.standard.commands.RunIf;
import org.usfirst.frc4904.standard.commands.RunIfElse;

public class BoringAuton extends CommandGroup {
Copy link
Member

Choose a reason for hiding this comment

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

RENAME THIS COMMAND POR FAVOR


public BoringAuton(DoubleSupplier betaSupplier, DoubleSupplier xSupplier, DoubleSupplier ySupplier) {
super("BoringAuton");
addSequential(new RunIfElse(
new BoringAutonPosX(betaSupplier, xSupplier, ySupplier), //the left of the robot is towards the positive x direction
new BoringAutonNegX(betaSupplier, xSupplier, ySupplier),
() -> xSupplier.getAsDouble() >= 0
));
addSequential(new ChassisMoveDistance(RobotMap.Component.chassis, () -> ySupplier.getAsDouble(), RobotMap.Component.drivePID));
}
public class BoringAutonPosX extends CommandGroup {
public BoringAutonPosX(DoubleSupplier betaSupplier, DoubleSupplier xSupplier, DoubleSupplier ySupplier) {
super("BoringAutonPosX"); //chassisturn and beta are positive to the right
addSequential(new ChassisTurn(RobotMap.Component.chassis, () -> 90 + betaSupplier.getAsDouble(), RobotMap.Component.navx, null, RobotMap.Component.chassisTurnMC));
addSequential(new ChassisMoveDistance(RobotMap.Component.chassis, () -> xSupplier.getAsDouble(), RobotMap.Component.drivePID));
addSequential(new ChassisTurn(RobotMap.Component.chassis, -90, RobotMap.Component.navx, null, RobotMap.Component.chassisTurnMC));
}
}
public class BoringAutonNegX extends CommandGroup {
public BoringAutonNegX(DoubleSupplier betaSupplier, DoubleSupplier xSupplier, DoubleSupplier ySupplier) {
super("BoringAutonNegX");
addSequential(new ChassisTurn(RobotMap.Component.chassis, () -> -90 + betaSupplier.getAsDouble(), RobotMap.Component.navx, null, RobotMap.Component.chassisTurnMC));
addSequential(new ChassisMoveDistance(RobotMap.Component.chassis, () -> -xSupplier.getAsDouble(), RobotMap.Component.drivePID));
addSequential(new ChassisTurn(RobotMap.Component.chassis, 90, RobotMap.Component.navx, null, RobotMap.Component.chassisTurnMC));
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
package org.usfirst.frc4904.robot.autonly;


import java.lang.Math;
import org.usfirst.frc4904.standard.commands.chassis.ChassisTurn;
import org.usfirst.frc4904.standard.commands.chassis.ChassisConstant;
import org.usfirst.frc4904.robot.RobotMap;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.CommandGroup;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import org.usfirst.frc4904.robot.autonly.UpdateableData;

/*
** The robot will drive forwards until it can see the white tape.
** Once the robot can see the white tape, it will stop and turn parallel to it.
*/

public class FloorTapeAutoAlign extends CommandGroup {
public double X = 0;
public double Y = 1;
public double TURN = 0;
public double TIMEOUT = 0;

public FloorTapeAutoAlign() {
super("FloorTapeAutoAlign");
addSequential(new DriveUntilTape());
addSequential(UpdateableData.update());
addSequential(new ChassisTurn(RobotMap.Component.chassis, UpdateableData.getBetaFloor.getAsDouble(), RobotMap.Component.navx,
RobotMap.Component.chassisTurnMC));
}
public class DriveUntilTape extends ChassisConstant {
public DriveUntilTape() {
super(RobotMap.Component.chassis, X, Y, TURN, TIMEOUT);
}

protected boolean isFinished() {
return UpdateableData.getIsFloorTapeVisible.getAsBoolean();
}
}
}
Loading