Skip to content

Commit

Permalink
final day changes
Browse files Browse the repository at this point in the history
  • Loading branch information
brandon-gong committed Feb 20, 2019
1 parent 1138246 commit 5346ace
Show file tree
Hide file tree
Showing 9 changed files with 473 additions and 352 deletions.
748 changes: 430 additions & 318 deletions dashboard_src/package-lock.json

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion dashboard_src/package.json
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
"homepage": "http://frcdashboard.github.io",
"devDependencies": {
"electron": "^1.7.12",
"electron-packager": "^10.1.1"
"electron-packager": "^13.0.1"
},
"dependencies": {
"wpilib-nt-client": "^1.7.1"
Expand Down
4 changes: 4 additions & 0 deletions dashboard_src/src/css/style.css
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,10 @@ header {
height: 80vh;
overflow: hidden;
background-color: #333;
background-image:url('http://frcvision.local:1181/?action=stream');
background-repeat: no-repeat;
backround-size: cover;

/* You'll need to mess with this a bit to get your camera to work. Replace the url with a live-updating image feed from your camera. Using other camera streaming systems will require some tweaking. */
/*background-image: url('LINK TO CAMERA SOURCE HERE');*/
}
Expand Down
20 changes: 10 additions & 10 deletions dashboard_src/src/ui.js
Original file line number Diff line number Diff line change
Expand Up @@ -25,16 +25,16 @@ let ui = {

// Gyro rotation
let updateGyro = (key, value) => {
ui.gyro.val = value;
ui.gyro.visualVal = Math.floor(ui.gyro.val - ui.gyro.offset);
ui.gyro.visualVal %= 360;
if (ui.gyro.visualVal < 0) {
ui.gyro.visualVal += 360;
}
ui.gyro.arm.style.transform = `rotate(${ui.gyro.visualVal}deg)`;
ui.gyro.number.innerHTML = ui.gyro.visualVal + 'º';
// ui.gyro.val = value;
// ui.gyro.visualVal = Math.floor(ui.gyro.val - ui.gyro.offset);
// ui.gyro.visualVal %= 360;
// if (ui.gyro.visualVal < 0) {
// ui.gyro.visualVal += 360;
// }
// ui.gyro.arm.style.transform = `rotate(${ui.gyro.visualVal}deg)`;
ui.gyro.number.innerHTML = value;
};
NetworkTables.addKeyListener('/SmartDashboard/drive/navx/yaw', updateGyro);
NetworkTables.addKeyListener('/SmartDashboard/hatchsolenoid1_status', updateGyro);

// The following case is an example, for a robot with an arm at the front.
NetworkTables.addKeyListener('/SmartDashboard/arm/encoder', (key, value) => {
Expand Down Expand Up @@ -108,4 +108,4 @@ ui.armPosition.oninput = function() {

addEventListener('error',(ev)=>{
ipc.send('windowError',{mesg:ev.message,file:ev.filename,lineNumber:ev.lineno})
})
})
8 changes: 5 additions & 3 deletions robot_src/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,10 @@ def robotInit(self):
)
self.lift = Lift(WPI_TalonSRX(3), wpilib.DigitalInput(0), wpilib.DigitalInput(1), self.stick)
self.arm = Arm(
wpilib.Solenoid(5,1),
wpilib.Solenoid(5,0),
wpilib.Solenoid(5,2),
wpilib.Solenoid(5,3),
wpilib.Solenoid(5,4),
wpilib.Solenoid(5,1),
wpilib.Solenoid(5,5),
self.stick
)
self.ballintake = BallIntake(WPI_TalonSRX(4))
Expand All @@ -70,13 +70,15 @@ def disabledPeriodic(self):
self.arm.log()
self.base.log()
self.ballintake.log()
wpilib.SmartDashboard.putNumber("visionerror", self.visiontable.getNumber("heading_error", 0))

# Called once on teleop start.
# Rezero lift encoder and rezero navx heading.
def teleopInit(self):
self.lift.initSensor()
self.base.navx.reset()


# Called repeatedly during teleop.
# Update all of the subsystems and log new data to SmartDashboard.
def teleopPeriodic(self):
Expand Down
4 changes: 2 additions & 2 deletions robot_src/subsystems/arm.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ def __init__(self, hs1, hs2, as1, as2, stick):

# the corresponding solenoids for each subsystem must be in opposite
# states.
self.hatchsolenoid1.set(True)
self.hatchsolenoid2.set(False)
self.hatchsolenoid1.set(False)
self.hatchsolenoid2.set(True)
self.armsolenoid1.set(True)
self.armsolenoid2.set(False)

Expand Down
4 changes: 2 additions & 2 deletions robot_src/subsystems/ballintake.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@ def update(self):
# 90, directly down is 180, etc. Center is -1.
if wpilib.DriverStation.getInstance().getStickPOV(0, 0) == -1:
self.motor.set(WPI_TalonSRX.ControlMode.PercentOutput, 0)
elif wpilib.DriverStation.getInstance().getStickPOV(0, 0) == 0:
self.motor.set(WPI_TalonSRX.ControlMode.PercentOutput, 1)
elif wpilib.DriverStation.getInstance().getStickPOV(0, 0) == 180:
self.motor.set(WPI_TalonSRX.ControlMode.PercentOutput, 1)
elif wpilib.DriverStation.getInstance().getStickPOV(0, 0) == 0:
self.motor.set(WPI_TalonSRX.ControlMode.PercentOutput, -1)

# Log values for the BallIntake for debug.
Expand Down
25 changes: 14 additions & 11 deletions robot_src/subsystems/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,11 @@ def __init__(self, fl, rl, fr, rr, navx, stick):
self.stick = stick
self.foctoggle = JoystickButton(self.stick,11)
self.focenabled = False
self.foctoggledown = False

# Ignore all joystick inputs that are below a certain threshold.
def deadband(self, val):
if abs(val) < .05:
if abs(val) < .2:
val = 0
return val

Expand All @@ -54,24 +55,26 @@ def update(self):

# You *cannot* use a simple if statement without the helper focenabled
# variable to toggle FOC state.
if self.foctoggle.get() and not self.focenabled:
self.focenabled = True
elif not self.foctoggle.get() and self.focenabled:
self.focenabled = False
if self.foctoggle.get() and not self.foctoggledown:
self.focenabled = not self.focenabled
self.foctoggledown = True
elif not self.foctoggle.get() and self.foctoggledown:
self.foctoggledown = False

scaleval = (1 - self.stick.getThrottle()) * 0.8 + 0.1
# Based on FOC state, decide whether or not to pass NavX heading.
if self.focenabled:
self.drive.driveCartesian(
self.deadband(self.stick.getX()),
-self.deadband(self.stick.getY()),
self.stick.getZ()*0.25,
self.deadband(self.stick.getX()) * scaleval * 2,
-self.deadband(self.stick.getY()) * scaleval,
self.stick.getZ()*0.25 * scaleval,
self.navx.getAngle()
)
else:
self.drive.driveCartesian(
self.deadband(self.stick.getX()),
-self.deadband(self.stick.getY()),
self.stick.getZ()*0.25
self.deadband(self.stick.getX()) * scaleval * 2,
-self.deadband(self.stick.getY()) * scaleval,
self.stick.getZ()*0.25 * scaleval
)

# Log as much data as possible to SmartDashboard for debug purposes.
Expand Down
10 changes: 5 additions & 5 deletions robot_src/subsystems/lift.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,13 @@ class Lift():
# Encoder constants for the lift.
# TODO recalibrate.
POSITION_MAX = -6.624 * (10**4)
POSITION_HATCH_TOP = -6.590 * (10**4)
POSITION_HATCH_MIDDLE = -3.547 * (10**4)
POSITION_HATCH_TOP = -6.300 * (10**4)
POSITION_HATCH_MIDDLE = -3.022 * (10**4)
POSITION_HATCH_BOTTOM = 0.000

POSITION_BALL_TOP = -6.324 * (10**4)
POSITION_BALL_MIDDLE = -5.670 * (10**4)
POSITION_BALL_BOTTOM = -2.632 * (10**4)
POSITION_BALL_TOP = -6.400 * (10**4)
POSITION_BALL_MIDDLE = -4.735 * (10**4)
POSITION_BALL_BOTTOM = -2.323 * (10**4)

POSITION_HUMAN_PLAYER = -3.993 * (10**4)

Expand Down

0 comments on commit 5346ace

Please sign in to comment.