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

now testing pixy cam #85

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
36 changes: 16 additions & 20 deletions src/main/java/frc/robot/subsystem/SubsystemFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import java.util.logging.Logger;

import frc.robot.OI;
import frc.robot.OzoneException;
import frc.robot.subsystem.climber.Climber;
import frc.robot.subsystem.controlpanel.ControlPanel;
import frc.robot.subsystem.controlpanel.commands.RotateToColor;
Expand Down Expand Up @@ -77,7 +78,7 @@ public void init(DisplayManager dm, PortMan portMan) throws Exception {

logger.info("initializing");

botName = getBotName();
// botName = getBotName();
botName = "football";

logger.info("Running on "+botName);
Expand All @@ -92,7 +93,7 @@ public void init(DisplayManager dm, PortMan portMan) throws Exception {
case "football": initFootball(portMan); break;
case "unknown": initFootball(portMan); break; // default to football if we don't know better
case "zombie": initZombie(portMan); break;
default: throw new Exception("Unrecognized MAC Address [" + activeMACs + "]");
// default: throw new Exception("Unrecognized MAC Address [" + activeMACs + "]");

}

Expand Down Expand Up @@ -152,13 +153,20 @@ private void initFootball(PortMan portMan) throws Exception {
transport = new Transport();
transport.init(portMan);
displayManager.addTransport(transport);

TakeIn tc = new TakeIn(transport);
OI.getInstance().bind(tc, OI.RightJoyButton4, OI.WhenPressed);

PushOut pc = new PushOut(transport);
OI.getInstance().bind(pc, OI.RightJoyButton3, OI.WhenPressed);


/**
* All of the Pixy Line stuff goes here
*/
pixyLineCam = new PixyLineCam();
pixyLineCam.init(portMan);
displayManager.addPixyLineCam(pixyLineCam);
PollPixyLine p = new PollPixyLine(pixyLineCam);
OI.getInstance().bind(p, OI.LeftJoyButton10, OI.WhenPressed);

/**
* All of the OneWheelShooter stuff goes here
*/
Expand All @@ -175,22 +183,10 @@ private void initFootball(PortMan portMan) throws Exception {
twoWheelShooter = new TwoWheelShooter();
twoWheelShooter.init(portMan);
displayManager.addTwoWheelShooter(twoWheelShooter);

Shoot sh2 = new Shoot(twoWheelShooter);
OI.getInstance().bind(sh2, OI.LeftJoyButton4, OI.WhenPressed);
Stop st2 = new Stop(twoWheelShooter);
OI.getInstance().bind(st2, OI.LeftJoyButton5, OI.WhenPressed);

/**
* All of the Pixy Line stuff goes here
*/
pixyLineCam = new PixyLineCam();
pixyLineCam.init(portMan);
displayManager.addPixyLineCam(pixyLineCam);

PollPixyLine p = new PollPixyLine(pixyLineCam);
OI.getInstance().bind(p, OI.LeftJoyButton1, OI.WhenPressed);

OI.getInstance().bind(st2, OI.LeftJoyButton5, OI.WhenPressed);

}

Expand All @@ -210,7 +206,7 @@ public Transport getTransport() {
return transport;
}

private String getBotName() {
/* private String getBotName() {

Enumeration<NetworkInterface> networks = NetworkInterface.getNetworkInterfaces();
String activeMACs = "";
Expand All @@ -223,7 +219,7 @@ private String getBotName() {
logger.info(" this MAC is for "+botName);
}
}
}
}*/

/**
* Formats the byte array representing the mac address as more human-readable form
Expand Down
49 changes: 30 additions & 19 deletions src/main/java/frc/robot/subsystem/pixylinecam/PixyLineCam.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,19 @@ public class PixyLineCam extends SubsystemBase{
private boolean leftStatus;
private boolean middleStatus;
private boolean rightStatus;
//logger variables
private String logX0;
private String logY0;
private String logX1;
private String logY1;
private String logIndex;
private String logFlags;
private String logArrayNumber;
private String logSlope;
private String logAngle;
private String logLeftStatus;
private String logMiddleStatus;
private String logRightStatus;

public PixyLineCam() {
}
Expand All @@ -54,44 +67,30 @@ public void resetPixyLine() {
}

public void init(PortMan portMan) {
logger.entering(PixyLineCam.class.getName(), "init()");

logger.info("initializing");
logger.info("Creating Pixy with link type of SPI");
pixy = Pixy2.createInstance(Pixy2.LinkType.SPI);
pixy.init(0);
logger.info("Here comes the version! :) " + pixy.getVersionInfo().toString());
line = pixy.getLine();

/* x0 = tab.add("Pixy x0", 0).getEntry();
y0 = tab.add("Pixy y0", 0).getEntry();
x1 = tab.add("Pixy x1", 0).getEntry();
y1 = tab.add("Pixy y1", 0).getEntry();
flags = tab.add("Pixy Flags", 0).getEntry();
index = tab.add("Pixy Index", 0).getEntry();
arrayNumber = tab.add("Number of Verticals", 0).getEntry();
slope = tab.add("Vector Slope", 0).getEntry();
angle = tab.add("Vector Angle", 0).getEntry();
leftStatus = tab.add("Left", false).getEntry();
middleStatus = tab.add("MIDDLE !!!!!!!", false).getEntry();
rightStatus = tab.add("Right", false).getEntry();
*/

}

}

public Pixy2Line getLine() {
logger.info("There's a line here");
return this.line;
}



public void writeLine(Pixy2Line.Vector line, int number) {
x0 = line.getX0();
y0 = line.getY0();
x1 = line.getX1();
y1 = line.getY1();
index = line.getIndex();
flags = line.getFlags();
arrayNumber = number;
arrayNumber = number;

//calculating slope
int vectorSlope = (line.getY0()-line.getY1())/(line.getX0()-line.getX1());
Expand Down Expand Up @@ -123,50 +122,62 @@ public void writeLine(Pixy2Line.Vector line, int number) {
}

public double getX0() {
logger.info("x0: " + x0);
return x0;
}

public double getY0() {
logger.info("y0: " + y0);
return y0;
}

public double getX1() {
logger.info("x1: " + x1);
return x1;
}

public double getY1() {
logger.info("y1: " + y1);
return y1;
}

public double getIndex() {
logger.info("index: " + index);
return index;
}

public double getFlags() {
logger.info("flags: " + flags);
return flags;
}

public int getArrayNumber() {
logger.info("array number: " + arrayNumber);
return arrayNumber;
}

public int getSlope() {
logger.info("slope: " + slope);
return slope;
}

public double getAngle() {
logger.info("angle: " + angle);
return angle;
}

public boolean getLeftStatus() {
logger.info("left status: " + leftStatus);
return leftStatus;
}

public boolean getMiddleStatus() {
logger.info("middle status: " + middleStatus);
return middleStatus;
}

public boolean getRightStatus() {
logger.info("right status: " + rightStatus);
return rightStatus;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
import java.util.logging.Logger;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystem.SubsystemFactory;
import frc.robot.subsystem.controlpanel.ControlPanel;
import frc.robot.subsystem.pixylinecam.PixyLineCam;

import io.github.pseudoresonance.pixy2api.Pixy2Line;
Expand Down