Skip to content
This repository has been archived by the owner on Feb 24, 2021. It is now read-only.

Commit

Permalink
Fix of Computer 3 client side code
Browse files Browse the repository at this point in the history
  • Loading branch information
hcshires committed Oct 28, 2019
1 parent 63f0ab6 commit c3c168b
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 26 deletions.
13 changes: 10 additions & 3 deletions .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,25 @@
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": [


{
"type": "java",
"name": "CodeLens (Launch) - Main",
"request": "launch",
"mainClass": "frc.robot.Main",
"projectName": "2019-FRC-Offseason-Code"
},
{
"type": "wpilib",
"name": "WPILib Desktop Debug",
"request": "launch",
"desktop": true,
"desktop": true
},
{
"type": "wpilib",
"name": "WPILib roboRIO Debug",
"request": "launch",
"desktop": false,
"desktop": false
}
]
}
16 changes: 1 addition & 15 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ public void robotInit() {

m_oi = new OI();
drivetrain = new DriveTrain();
arm = new Arm();

/* PD
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
Expand Down Expand Up @@ -129,21 +130,13 @@ public void teleopInit() {
public void teleopPeriodic() {
Scheduler.getInstance().run();

/* Hatch Panel Checker */
m_oi.getArmUpBtn().whileActive(new HandleArm(RobotMap.armPower)); // Raise Hatch Panel
m_oi.getArmDownBtn().whileActive(new HandleArm(-RobotMap.armPower)); // Lower Hatch Panel


/* PD
Update_Limelight_Tracking();
double steer = m_Controller.getX(Hand.kRight);
double drive = -m_Controller.getY(Hand.kLeft);
boolean auto = m_Controller.getAButton();
steer *= 0.70;
drive *= 0.70;
if (auto)
{
if (m_LimelightHasValidTarget)
Expand Down Expand Up @@ -176,33 +169,26 @@ public void testPeriodic() {
final double DRIVE_K = 0.26; // how hard to drive fwd toward the target
final double DESIRED_TARGET_AREA = 13.0; // Area of the target when the robot reaches the wall
final double MAX_DRIVE = 0.7; // Simple speed limit so we don't drive too fast
double tv = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0);
double tx = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tx").getDouble(0);
double ty = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0);
double ta = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ta").getDouble(0);
boolean m_LimelightHasValidTarget;
double m_LimelightDriveCommand;
double m_LimelightSteerCommand;
if (tv < 1.0)
{
m_LimelightHasValidTarget = false;
m_LimelightDriveCommand = 0.0;
m_LimelightSteerCommand = 0.0;
return;
}
m_LimelightHasValidTarget = true;
// Start with proportional steering
double steer_cmd = tx * STEER_K;
m_LimelightSteerCommand = steer_cmd;
// try to drive forward until the target area reaches our desired area
double drive_cmd = (DESIRED_TARGET_AREA - ta) * DRIVE_K;
// don't let the robot drive too fast into the goal
if (drive_cmd > MAX_DRIVE)
{
Expand Down
11 changes: 4 additions & 7 deletions src/main/java/frc/robot/commands/HandleArm.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,9 @@
import frc.robot.RobotMap;

public class HandleArm extends Command {
private double motorPower;

public HandleArm(double power) {
public HandleArm() {
requires(Robot.arm);

this.motorPower = power;
}

// Called just before this Command runs the first time
Expand All @@ -30,9 +27,9 @@ protected void initialize() {
@Override
protected void execute() {
if (Robot.m_oi.isArmDownPressed()){
Robot.arm.armMotor(1);
Robot.arm.armMotor(-RobotMap.armPower);
}else if(Robot.m_oi.isArmUpPressed()){
Robot.arm.armMotor(0);
Robot.arm.armMotor(RobotMap.armPower);
}
}

Expand All @@ -53,4 +50,4 @@ protected void end() {
protected void interrupted() {
Robot.arm.armMotor(0.0);
}
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public Arm() {

@Override
protected void initDefaultCommand() {
setDefaultCommand(new HandleArm(0.0));
setDefaultCommand(new HandleArm());
}


Expand Down

0 comments on commit c3c168b

Please sign in to comment.