Skip to content
This repository has been archived by the owner on Sep 14, 2019. It is now read-only.

First commit of DavidRobot2018 #5

Merged
merged 8 commits into from
Jan 15, 2018
2 changes: 2 additions & 0 deletions Robot2018/.classpath
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,7 @@
<classpathentry kind="var" path="opencv" sourcepath="opencv.sources"/>
<classpathentry kind="var" path="cscore" sourcepath="cscore.sources"/>
<classpathentry kind="var" path="wpiutil" sourcepath="wpiutil.sources"/>
<classpathentry kind="lib" path="/Robot2017/libs/jars/navx_frc.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRE_Phoenix.jar"/>
<classpathentry kind="output" path="bin"/>
</classpath>
37 changes: 36 additions & 1 deletion Robot2018/src/org/usfirst/frc/team199/Robot2018/OI.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,18 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/

package org.usfirst.frc.team199.Robot2018;

import edu.wpi.first.wpilibj.buttons.Button;
import org.usfirst.frc.team199.Robot2018.commands.ShiftLowGear;
import org.usfirst.frc.team199.Robot2018.commands.ShiftDriveType;

import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
* This class is the glue that binds the controls on the physical operator
Expand Down Expand Up @@ -34,4 +46,27 @@ public class OI {
// Start the command when the button is released and let it run the command
// until it is finished as determined by it's isFinished method.
// button.whenReleased(new ExampleCommand());

public Joystick leftJoy;
public JoystickButton shiftDrive;
public JoystickButton shiftDriveType;
public Joystick rightJoy;
public Joystick manipulator;


public int getButton(String key, int def) {
Copy link
Member

Choose a reason for hiding this comment

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

Do these need to be public for some reason?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The joysticks need to be public because their values are needed in some functions. I have no clue about the buttons, however, that's how we did it last year so that's how I did it this week.

Copy link
Member

Choose a reason for hiding this comment

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

I agree on the Joysticks. I saw they were being used after writing my comment.
I don't see any need to make the buttons public. It just makes it easier to introduce unnecessary dependencies. I recommend making them private for now and reevaluate if you find they need to be accessed from other classes.

if(!SmartDashboard.containsKey(key)) {
SmartDashboard.putNumber(key, def);
}
return (int) SmartDashboard.getNumber(key, def);
}
public OI() {
leftJoy = new Joystick(0);
shiftDrive = new JoystickButton(leftJoy, getButton("Button Shift Drive", 1));
shiftDrive.whenPressed(new ShiftLowGear());
shiftDriveType = new JoystickButton(leftJoy, getButton("Button Shift Drive Type", 2));
shiftDriveType.whenPressed(new ShiftDriveType());
rightJoy = new Joystick(1);
Copy link
Member

Choose a reason for hiding this comment

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

The names shiftDrive and shiftDriveType (and the corresponding terminology in the strings) is confusing. Would better names be something like "shift to low gear" and "toggle (or switch) drive type"?

Has anyone interviewed the operators to determine how they want the controls to work.

Also, can we create a picture and/or instructions which are accessible from the SmartDashboard which describes how the controls work. That picture/instructions would be maintained and committed beside the code and there should be a prominent comment in OI.java indicating that the picture/instructions need to be updated when the code is changed.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

No longer relevant; see 9083d16
According to Laura, according to offseason experience drivers preferred this split.
Last year, I managed (admittedly pretty poorly) manipulator diagrams, this year I can hand that off to a rookie :)

Copy link
Member

Choose a reason for hiding this comment

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

All good on the first 2 points.

Regarding the manip diagrams, please create an issue/card to make sure this doesn't get dropped.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

manipulator = new Joystick(2);
}
}
33 changes: 33 additions & 0 deletions Robot2018/src/org/usfirst/frc/team199/Robot2018/Robot.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,11 @@

package org.usfirst.frc.team199.Robot2018;

import java.util.ArrayList;

import org.usfirst.frc.team199.Robot2018.subsystems.Climber;
import org.usfirst.frc.team199.Robot2018.subsystems.ClimberAssist;
import org.usfirst.frc.team199.Robot2018.subsystems.Drivetrain;
import org.usfirst.frc.team199.Robot2018.subsystems.IntakeEject;
import org.usfirst.frc.team199.Robot2018.subsystems.Lift;

Expand All @@ -26,18 +29,48 @@ public class Robot extends IterativeRobot {
public static final ClimberAssist climberAssist = new ClimberAssist();
public static final IntakeEject intakeEject = new IntakeEject();
public static final Lift lift = new Lift();
public static Drivetrain dt;

public static OI oi;

Command autonomousCommand;
SendableChooser<Command> chooser = new SendableChooser<>();


public static double getConst(String key, double def) {
if(!SmartDashboard.containsKey(key)) {
SmartDashboard.putNumber(key, def);
}
return SmartDashboard.getNumber(key, def);
}
public void sendValuesToDashboard() {
Copy link
Member

Choose a reason for hiding this comment

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

Would setDashboardDefaults be a better name for this method?
Does it need to be public?

ArrayList<String> boolKeys = new ArrayList<String>();
ArrayList<Boolean> boolDef = new ArrayList<Boolean>();
boolKeys.add("Arcade Drive");
boolKeys.add("Arcade Drive Default Setup");
boolKeys.add("Square Drive Values");
boolKeys.add("High Gear");

boolDef.add(true);
boolDef.add(true);
boolDef.add(false);
boolDef.add(false);
for(int i = 0; i < boolKeys.size(); i++) {
if(!SmartDashboard.containsKey(boolKeys.get(i))) {
SmartDashboard.putBoolean(boolKeys.get(i), boolDef.get(i));
}
}
Copy link
Member

Choose a reason for hiding this comment

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

I don't see the need to iterate through arrays here. Seems it would be much clearer and less error prone if written explicitly as something like:

setDefault("Arcade Drive", true);
setDefault("Arcade Drive Default Setup", true);
etc.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Changed to same standard as other SD values in latest commit

}

/**
* This function is run when the robot is first started up and should be
* used for any initialization code.
*/
@Override
public void robotInit() {
dt = new Drivetrain();
oi = new OI();
sendValuesToDashboard();
// chooser.addObject("My Auto", new MyAutoCommand());
SmartDashboard.putData("Auto mode", chooser);
}
Expand Down
106 changes: 106 additions & 0 deletions Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,24 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/

package org.usfirst.frc.team199.Robot2018;

import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.kauailabs.navx.frc.AHRS;

import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PIDController;
import edu.wpi.first.wpilibj.SerialPort;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
* The RobotMap is a mapping from the ports sensors and actuators are wired into
* to a variable name. This provides flexibility changing wiring, makes checking
Expand All @@ -16,4 +35,91 @@ public class RobotMap {
// number and the module. For example you with a rangefinder:
// public static int rangefinderPort = 1;
// public static int rangefinderModule = 1;

public static Encoder leftEnc;
public static WPI_TalonSRX dtLeftDrive;
public static WPI_TalonSRX dtLeftSlave;
public static SpeedControllerGroup dtLeft;

public static Encoder rightEnc;
public static WPI_TalonSRX dtRightDrive;
public static WPI_TalonSRX dtRightSlave;
public static SpeedControllerGroup dtRight;
public static DifferentialDrive robotDrive;
public static PIDController turnController;
public static PIDController moveController;
// public static PIDController moveLeftController;
// public static PIDController moveRightController;

public static AHRS ahrs;
public static AnalogGyro dtGyro;
public static DoubleSolenoid dtGear;

private void configSRX(WPI_TalonSRX mc) {
int kTimeout = (int) Robot.getConst("ConstkTimeoutMs", 10);
mc.configNominalOutputForward(0, kTimeout);
mc.configNominalOutputReverse(0, kTimeout);
mc.configPeakOutputForward(1, kTimeout);
mc.configPeakOutputReverse(-1, kTimeout);
}
public RobotMap() {

leftEnc = new Encoder(getPort("Port1LeftEnc", 0), getPort("Port2LeftEnc", 1));
dtLeftDrive = new WPI_TalonSRX(getPort("PortLeftTalonSRXDrive", 1));
configSRX(dtLeftDrive);
dtLeftSlave = new WPI_TalonSRX(getPort("PortLeftTalonSRXSlave", 1));
configSRX(dtLeftSlave);
dtLeft = new SpeedControllerGroup(dtLeftDrive, dtLeftSlave);

rightEnc = new Encoder(getPort("Port1RightEnc", 2), getPort("Port2RightEnc", 3));
dtRightDrive = new WPI_TalonSRX(getPort("PortRightTalonSRXDrive", 2));
configSRX(dtRightDrive);
dtRightSlave = new WPI_TalonSRX(getPort("PortRightTalonSRXSlave", 1));
Copy link
Member

Choose a reason for hiding this comment

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

Shouldn't all of the default values for the ports above be different from each other?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Different types of sensors (PWM, CAN) each has their own index list starting at 0.

Copy link
Member

Choose a reason for hiding this comment

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

But aren't all of the TalonSRX's on the same bus (CAN)? Why do 3 out of 4 default to 1?

Copy link
Member

Choose a reason for hiding this comment

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

I see this is fixed now.

configSRX(dtRightSlave);
dtRight = new SpeedControllerGroup(dtRightDrive, dtRightSlave);

robotDrive = new DifferentialDrive(dtLeft, dtRight);
turnController = new PIDController(Robot.getConst("ConstTurnkP", 1), Robot.getConst("ConstTurnkI", 0), Robot.getConst("ConstTurnkD", 0), ahrs, Robot.dt);
turnController.disable();
turnController.setInputRange(-180, 180);
turnController.setOutputRange(-1.0, 1.0);
turnController.setContinuous();
turnController.setAbsoluteTolerance(Robot.getConst("ConstTurnTolerance", 1));
moveController = new PIDController(Robot.getConst("ConstMovekP", 1), Robot.getConst("ConstMovekI", 0), Robot.getConst("ConstMovekD", 0), Robot.dt, Robot.dt);
turnController.disable();
turnController.setInputRange(-180, 180);
turnController.setOutputRange(-1.0, 1.0);
turnController.setContinuous();
turnController.setAbsoluteTolerance(Robot.getConst("ConstMoveTolerance", 2));
// moveLeftController = new PIDController(Robot.getConst("ConstMoveLeftkP", 1), Robot.getConst("ConstMoveLeftkI", 0), Robot.getConst("ConstMoveLeftkD", 0), Robot.dt.getLeftDrive(), (PIDOutput) Robot.dt.getLeftDrive());
// moveLeftController.disable();
// moveLeftController.setInputRange(0, Double.MAX_VALUE);
// moveLeftController.setOutputRange(-1.0, 1.0);
// moveLeftController.setContinuous(false);
// moveLeftController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceLeft", 2));
// moveRightController = new PIDController(Robot.getConst("ConstMoveRightkP", 1), Robot.getConst("ConstMoveRightkI", 0), Robot.getConst("ConstMoveRightkD", 0), Robot.dt.getRightDrive(), (PIDOutput) Robot.dt.getRightDrive());
// moveRightController.disable();
// moveRightController.setInputRange(0, Double.MAX_VALUE);
// moveRightController.setOutputRange(-1.0, 1.0);
// moveRightController.setContinuous(false);
// moveRightController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight", 2));

ahrs = new AHRS(SerialPort.Port.kMXP);
dtGyro = new AnalogGyro(getPort("PortGyro", 0));
dtGear = new DoubleSolenoid(getPort("Port1dtGearSolenoid", 0), getPort("Port2dtGearSolenoid", 1));

}

/**
* Used in RobotMap to find ports for robot components, getPort also puts numbers if they don't exist yet.
* @param key The port key
* @param def The default value
* @return returns the Port
*/
public int getPort(String key, int def) {
if(!SmartDashboard.containsKey(key)) {
SmartDashboard.putNumber(key, def);
}
return (int)SmartDashboard.getNumber(key, def);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
package org.usfirst.frc.team199.Robot2018.commands;

import org.usfirst.frc.team199.Robot2018.Robot;

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

/**
*
*/
public class PIDDrive extends Command {
Copy link
Member

Choose a reason for hiding this comment

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

Need a comment describing what this command is supposed to do. My guess is that it is intended to use pid to drive a target distance straight forward. However, it doesn't look like it will do that since it seems to always send the same value to both motors. Mechanical and electrical differences between the left and right side of the drivetrain will cause them not to move at the same speed for the same value, and the robot will drift left or right.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Drivetrain implements PIDOutput (hopefully correctly) so the value does change. Differences can/should be accounted for by the PID constants.

Copy link
Member

Choose a reason for hiding this comment

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

The value changes over time due to Drivetrain's PID code, but at any given time the same value is sent directly to both motor controllers. What am I missing?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I don't currently have a "correct" fix to the proposed issue; more research would be required. One possible fix could be adding coefficients in the Drivetrain class so that callers can assume that both sides run equally.

Copy link
Member

Choose a reason for hiding this comment

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

Moved to issue #28


double target;
public PIDDrive(double targ) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
target = targ;
requires(Robot.dt);
Copy link
Contributor

Choose a reason for hiding this comment

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

Once you create an interface for the Drivetrain (which will be the next step), you can great a local variable in this class of the type DrivetrainInterface so you don't have to call Robot.dt every time

}

// Called just before this Command runs the first time
protected void initialize() {
Robot.dt.enableMovePid();
Robot.dt.setSetMove(target);
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.dt.arcadeDrive(Robot.dt.getPidOut(), 0);
}

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

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

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
package org.usfirst.frc.team199.Robot2018.commands;

import org.usfirst.frc.team199.Robot2018.Robot;
import org.usfirst.frc.team199.Robot2018.RobotMap;

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

/**
*
*/
public class PIDTurn extends Command {
Copy link
Member

Choose a reason for hiding this comment

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

Please see my comments on PIDDrive. They apply here as well. In this case the assymetries will cause the robot to move somewhat forward or backward when attempting to turn in place.


double target;
public PIDTurn(double targ) {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
target = targ;
requires(Robot.dt);
}

// Called just before this Command runs the first time
protected void initialize() {
Robot.dt.resetAHRS();
Robot.dt.setSetTurn(target);
Robot.dt.enableTurnPid();
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.dt.arcadeDrive(0, Robot.dt.getPidOut());
}

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

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

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
end();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package org.usfirst.frc.team199.Robot2018.commands;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
*
*/
public class ShiftDriveType extends Command {

Timer tim;
public ShiftDriveType() {
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
}

// Called just before this Command runs the first time
protected void initialize() {
tim = new Timer();
tim.reset();
tim.start();
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
SmartDashboard.putBoolean("Arcade Drive", !SmartDashboard.getBoolean("Arcade Drive", false));
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return tim.get() > 0.125;
Copy link
Member

Choose a reason for hiding this comment

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

Isn't there a more reliable and clear way to do this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

This command just switches the boolean value; the person who implements JUnit test will be responsible for commenting the code.

Copy link
Member

@brettle brettle Jan 18, 2018

Choose a reason for hiding this comment

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

After another look, I'm pretty sure this code is just plain broken. Looks like it will toggle the value of "Arcade Drive" repeatedly (~every 20ms) for at least 125ms, leaving it in a psuedorandom state.

On a separate note, the person who writes the code is generally responsible for writing appropriate comments.

Copy link
Member

Choose a reason for hiding this comment

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

My bad. I see it's not broken now. Still unnecessarily confusing. Moved to issue #30.

}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}
}
Loading